mobile_manipulator_robot_control/config/controllers.yaml

joint_state_controller:
  type: joint_state_controller/JointStateController
  publish_rate: 20

base_controller:
  type        : "diff_drive_controller/DiffDriveController"
  left_wheel  : 'l_wheel_joint'
  right_wheel : 'r_wheel_joint'
  publish_rate: 40.0               # default: 50
  pose_covariance_diagonal: [0.001, 0.001, 0.001, 0.001, 0.001, 0.03]
  twist_covariance_diagonal: [0.001, 0.001, 0.001, 0.001, 0.001, 0.03]
  enable_odom_tf: true

  # Wheel separation and diameter. These are both optional.
  # diff_drive_controller will attempt to read either one or both from the
  # URDF if not specified as a parameter
  wheel_separation : 0.76
  wheel_radius : 0.1

  # Wheel separation and radius multipliers
  wheel_separation_multiplier: 1.0 # default: 1.0
  wheel_radius_multiplier    : 1.0 # default: 1.0

  # Velocity commands timeout [s], default 0.5
  cmd_vel_timeout: 0.5

  # Base frame_id
  base_frame_id: base_footprint #default: base_link
  odom_frame_id: odom

  # Velocity and acceleration limits
  # Whenever a min_* is unspecified, default to -max_*
  linear:
    x:
      has_velocity_limits    : true
      max_velocity           : 1.2 # m/s
      # min_velocity           : -0.15 # m/s
      has_acceleration_limits: true
      max_acceleration       : 1.8  # m/s^2
      # min_acceleration       : -1.6 # m/s^2
  angular:
    z:
      has_velocity_limits    : true
      max_velocity           : 2.0  # rad/s
      has_acceleration_limits: true
      max_acceleration       : 3.0  # rad/s^2

arm_controller:
  type: position_controllers/JointTrajectoryController
  joints:
    - ur5e_shoulder_pan_joint
    - ur5e_shoulder_lift_joint
    - ur5e_elbow_joint
    - ur5e_wrist_1_joint
    - ur5e_wrist_2_joint
    - ur5e_wrist_3_joint
  constraints:
      goal_time: 0.6
      stopped_velocity_tolerance: 0.05
      ur5e_shoulder_pan_joint: {trajectory: 0.1, goal: 0.1}
      ur5e_shoulder_lift_joint: {trajectory: 0.1, goal: 0.1}
      ur5e_elbow_joint: {trajectory: 0.1, goal: 0.1}
      ur5e_wrist_1_joint: {trajectory: 0.1, goal: 0.1}
      ur5e_wrist_2_joint: {trajectory: 0.1, goal: 0.1}
      ur5e_wrist_3_joint: {trajectory: 0.1, goal: 0.1}
  stop_trajectory_duration: 0.5
  state_publish_rate:  25
  action_monitor_rate: 10

gripper_controller:
  type: position_controllers/JointPositionController
  joint: finger_joint

mobile_manipulator_robot_control/launch/bringup_controller.launch

<launch>
  <rosparam file="$(find mobile_manipulator_robot_control)/config/controllers.yaml" command="load"/>
  <node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="true"
          output="screen" args="  joint_state_controller
                                  base_controller
                                  arm_controller
                                  gripper_controller">
  </node>
</launch>