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

How to control a rotating joint in velocity

asked 2019-12-02 09:54:02 -0500

lotfishtaine gravatar image

Hello everyone,

I'm trying to control a rotating joint type "continuous" in velocity, and simulate it in Gazebo.

This is the URDF joint definition:

<joint name="${name}_joint" type="continuous"> 
      <xacro:insert_block name="origin" />
      <parent link="${namespace}/${parent}"/>
      <child link="${namespace}/${name}"/>
      <axis xyz="1 0 0" rpy="0 0 0" />
      <limit effort="2000.0" velocity="40.0" />
    </joint>

    <gazebo>
      <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
        <robotNamespace>${namespace}</robotNamespace>
      </plugin>
    </gazebo>

    <transmission name="${name}_joint_trans">
      <type>transmission_interface/SimpleTransmission</type>
      <joint name="${name}_joint">
        <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
      </joint>
      <actuator name="${name}_joint_motor">
        <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
        <mechanicalReduction>1</mechanicalReduction>
      </actuator>
    </transmission>

and the config yaml file for controllers:

 joint_state_controller:
    type: joint_state_controller/JointStateController
    publish_rate: 60

  my_joint_position_controller:
    type: velocity_controllers/JointVelocityController
    joint: my_joint
    pid: {p: 0.5, i: 0.6, d: 0.0035}

I have couple of questions:

  • first, can someone explain the yaml file or give a tutorial explaining this? what is "publish_rate" and what is its role? how can influence the rotation? same for "joint_state_controller"?

  • Second, to change the joint velocity I run :

    rostopic pub /my_joint_position_controller/command std_msgs/Float64 "data: 5.0"

    the data value is a linear velocity (m/s) or rotational velocity (rad/s) ? If it is a linear velocity, how can I transform that to rotational velocity (rad/s)?

  • third, how can I get the joint angle at every moment?

Thanks in advance.

edit retag flag offensive close merge delete

Comments

In my implementation, I followed this tutorial and managed to control the joint. However, when I get to the controller performance visualization part, I can't find the topic my_joint_position_controller/state/process_value

Does this mean that I'm missing something in my implementation?

lotfishtaine gravatar image lotfishtaine  ( 2019-12-04 03:28:59 -0500 )edit

state/process_value is not a topic. It's a field in the message that is published on the state topic.

See also #q323036.

rqt_plot is just able to "reach into" messages to plot values from fields. That makes it seem like they are topics, but they're not (rostopic can do the same).

gvdhoorn gravatar image gvdhoorn  ( 2019-12-04 03:34:34 -0500 )edit

Thank you for your reply. When you said state topic, do you mean /joint_states topic or another topic? rostopic list command only gives me one topic related to my joint controller:

- `my_joint_position_controller/command`

Should I have another topic or not? like :

  - my_joint_position_controller/pid/parameter_descriptions
  - my_joint_position_controller/pid/parameter_updates
  - my_joint_position_controller/state

same in this example.

lotfishtaine gravatar image lotfishtaine  ( 2019-12-04 07:59:23 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2019-12-12 09:16:04 -0500

lotfishtaine gravatar image

1- the yaml file is basically describe the used controllers. It always contains the joint_state_controller which is in charge of providing constant information about the state of the joint, and the description of the other controllers. The /joint_states topic is published by an instance of the JointStateController. This is a read-only controller that does not command any joint, but rather publishes the current joint states at a configurable frequency (publish_rate).

2- the inputs to ros controllers are always in SI units, so a joint velocity controller will accept radians per second.

3- joint_state_controller: it continuously provides the state of the joint.

4- for the question in the comment, I think that it is a bug with velocity_controllers which prevent the topic my_joint_position_controller/state to be published. I changed the controller to effort_controllers/JointVelocityController and I get this topic.

5- a nice tutorial explaining ros_control can be found here.

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2019-12-02 09:54:02 -0500

Seen: 1,453 times

Last updated: Dec 12 '19