ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Launching the JointGroupVelocityController

asked 2019-07-01 01:45:46 -0500

Jarvis1997 gravatar image

I have some problems in launching the jointGroupVelocityController.

This was my .yaml file before:

joint_state_controller:
    type: joint_state_controller/JointStateController
    publish_rate: 50
joint_fr_motor_controller:
    type: velocity_controllers/JointVelocityController
    joint: joint_front_right_prop
    pid: {p: 10000, i: 1, d: 1000}
joint_fl_motor_controller:
    type: velocity_controllers/JointVelocityController
    joint: joint_front_left_prop
    pid: {p: 10000, i: 1, d: 1000}
joint_br_motor_controller:
    type: velocity_controllers/JointVelocityController
    joint: joint_back_right_prop
    pid: {p: 10000, i: 1, d: 1000}
joint_bl_motor_controller:
    type: velocity_controllers/JointVelocityController
    joint: joint_back_left_prop
    pid: {p: 10000, i: 1, d: 1000}

In this way, I cannot provide velocities SIMULTANEOUSLY to all the four joints. I have a .launch file that loads all these controllers, using the controller_manager pkg. This is the snippet of the controller_manager in my .launch file:

<group ns="Kwad">
    ..................
    <node name="control_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen" args="--namespace=/Kwad
    /Kwad/joint_state_controller
    /Kwad/joint_fr_motor_controller
    /Kwad/joint_fl_motor_controller
    /Kwad/joint_bl_motor_controller
    /Kwad/joint_br_motor_controller" />
    ....................
</group>

I came across the JointGroupVelocityController, that provides multiple velocities to the joints SIMULTANEOUSLY, thus I want to know how to change the .yaml file and the .launch file accordingly.

This is my updated .yaml file, but i am not sure if it's correct:

joint_state_controller:
    type: joint_state_controller/JointStateController
    publish_rate: 50
joint_motor_controller:
    type: velocity_controllers/JointGroupVelocityController
    joint: 
        - joint_front_right_prop
        - joint_front_left_prop
        - joint_back_left_prop
        - joint_back_right_prop
    pid: {p: 10000, i: 1, d: 1000}

Can someone please help me out?

Thank you.

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
4

answered 2019-07-01 05:17:05 -0500

Jarvis1997 gravatar image

I found the solution.

The .yaml file must be as follows:

joint_state_controller:
    type: joint_state_controller/JointStateController
    publish_rate: 50
joint_motor_controller:
    type: velocity_controllers/JointGroupVelocityController
    joints: 
        - joint_front_right_prop
        - joint_front_left_prop
        - joint_back_left_prop
        - joint_back_right_prop
gains:
    joint_front_right_prop: {p: 10000, i: 1, d: 1000}
    joint_front_left_prop: {p: 10000, i: 1, d: 1000}
    joint_back_left_prop: {p: 10000, i: 1, d: 1000}
    joint_back_right_prop: {p: 10000, i: 1, d: 1000}

Make sure to change "joint" to "joints". These must include the joints you have defined in the .xacro file. In my case, it is joint_front_right_prop, joint_front_left_prop, joint_back_left_prop, joint_back_right_prop.

Also, my launch file is:

<node name="control_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen" args="--namespace=/Kwad joint_state_controller 
                         joint_motor_controller" />

This launches all four joints at the same time, and SIMULTANEOUSLY publishes velocities to these four joints.

The command initially was:

rostopic pub -1 /Kwad/joint_front_right_prop/command std_msgs/Float64 "data: 10"

I had to repeat this command 4 times for 4 different joints. Now it is the follows. One command for four joints.

rostopic pub -1 /Kwad/joint_motor_controller/command std_msgs/Float64MultiArray "data: [10, 10, 10, 10]"

This publishes velocity of 10 units (in Gazebo world) to all the 4 joints, SIMULTANEOUSLY.

I hope this helps anyone in need. Thank you!!

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2019-07-01 01:45:46 -0500

Seen: 1,422 times

Last updated: Jul 01 '19