@@ -19,6 +19,10 @@ controller_manager:
1919 type : velocity_force_controller/VelocityForceController
2020 arm_only_velocity_force_controller :
2121 type : velocity_force_controller/VelocityForceController
22+ joint_velocity_controller :
23+ type : joint_velocity_controller/JointVelocityController
24+ arm_only_joint_velocity_controller :
25+ type : joint_velocity_controller/JointVelocityController
2226
2327vacuum_gripper :
2428 ros__parameters :
@@ -487,3 +491,82 @@ arm_only_velocity_force_controller:
487491 command_timeout : 0.2
488492 # Padding (in radians) to add to joint position limits as a safety margin.
489493 joint_limit_position_tolerance : 0.02
494+
495+ joint_velocity_controller :
496+ ros__parameters :
497+ # Joint group to control.
498+ planning_group_name : manipulator
499+ command_joints :
500+ - platform_velocity_controller/linear_x_joint
501+ - platform_velocity_controller/linear_y_joint
502+ - platform_velocity_controller/rotational_yaw_joint
503+ - shoulder_pan_joint
504+ - shoulder_lift_joint
505+ - elbow_joint
506+ - wrist_1_joint
507+ - wrist_2_joint
508+ - wrist_3_joint
509+ # Maximum joint-space velocities.
510+ max_joint_velocity :
511+ - 1.0
512+ - 1.0
513+ - 1.0
514+ - 1.0
515+ - 1.0
516+ - 1.0
517+ - 1.0
518+ - 1.0
519+ - 1.0
520+ # Maximum joint-space accelerations.
521+ max_joint_acceleration :
522+ - 2.0
523+ - 2.0
524+ - 2.0
525+ - 2.0
526+ - 2.0
527+ - 2.0
528+ - 2.0
529+ - 2.0
530+ - 2.0
531+ command_interfaces : ["velocity"]
532+ # Padding (in radians) to add to joint position limits as a safety margin.
533+ joint_limit_position_tolerance : 0.02
534+ # Timeout in seconds after which the controller will stop motion if no new commands are received.
535+ command_timeout : 0.2
536+ # Rate in Hz at which the controller will publish the state.
537+ state_publish_rate : 20
538+
539+ arm_only_joint_velocity_controller :
540+ ros__parameters :
541+ # Joint group to control.
542+ planning_group_name : arm_only
543+ command_joints :
544+ - shoulder_pan_joint
545+ - shoulder_lift_joint
546+ - elbow_joint
547+ - wrist_1_joint
548+ - wrist_2_joint
549+ - wrist_3_joint
550+ # Maximum joint-space velocities.
551+ max_joint_velocity :
552+ - 1.0
553+ - 1.0
554+ - 1.0
555+ - 1.0
556+ - 1.0
557+ - 1.0
558+ # Maximum joint-space accelerations.
559+ max_joint_acceleration :
560+ - 2.0
561+ - 2.0
562+ - 2.0
563+ - 2.0
564+ - 2.0
565+ - 2.0
566+ command_interfaces : ["velocity"]
567+ # Padding (in radians) to add to joint position limits as a safety margin.
568+ joint_limit_position_tolerance : 0.02
569+ # Timeout in seconds after which the controller will stop motion if no new commands are received.
570+ command_timeout : 0.2
571+ # Rate in Hz at which the controller will publish the state.
572+ state_publish_rate : 20
0 commit comments