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

ROS2 joint_trajectory_controllers sync with hardware execution

asked 2021-04-15 10:22:49 -0500

ravnicas gravatar image

updated 2021-04-15 11:13:09 -0500

I've got a question about ros2_control, the hardware_interface syncronisation to be exact.

I've read through most of the examples and got a working model with ros_control, joint_trajectory_controller and a demo hardware_interface which just echos the input. Now i'd like to implement a the real communication to my robot.

The communication between the hardware interface and the robot should be implemented packet wise. So that im sending the first 10 joint configuration commands, which will be executed sequentially. As soon as the robot copies its buffer, it sets a flag so i can write the next 10 commands to be executed. This part i dont want to change, as existing software is already implemented in this fashion.

Now i dont quite get the behavior of the joint trajectory interface in combination with the hardware interface demo.

the read function is just straight copied from the new panda example:

return_type GenericSystem::read()
{
// do loopback
joint_states_ = joint_commands_;
other_states_ = other_commands_;

if (fake_sensor_command_interfaces_)
{
  sensor_states_ = sensor_fake_commands_;
}
return return_type::OK;
}

Here i can see the commands are getting written to the hw_interface independetly of the state. Even if remove the loopback part, the commands are still reaching the interface. So the question arises, can i also give a feedback to the controller dependent on the buffer state. The frequency of the written commands isnt as important, and i still have the possibility to sample the hardware joint states with an arbitrary frequency.

So i'd like to make the write dependent on the robots internal status bits.

Edit:

After further reading i got that the write command can return a return_type::ERROR.

Would the following construct be a legitimate solution:

return_type GenericSystem::write()
{
    if(robot_busy == false)
    {
        write_to_robot();
        return OK;
    }
    else
    {
        // this would repeat the joint command as soon as the next cycle happens, if i understand correctly
        return ERROR;
    }
}
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2021-11-25 09:48:21 -0500

Hi, thanks for interest in ros2_control.

Let me first clarify how ros2_control's update loop is working:

  1. read() method of hardware is called to read current states from a hardware
  2. update() of all active controllers is called where based on states new commands are written
  3. write() method of hardware is called to write new commands to a hardware

The states and commands members are shared between hardware and controllers so that both have access to the same memory locations for reading/writing data.

Following that, yes, you will get each time when write is called a new command. (if controller received command, otherwise the same value will be written over and over again.

Return of return_type::ERROR is used for error management during read and write methods. This should ne be usually used, but only when "a real" error happens, like communication is broken or similar. The framework calls automatically on_error method when this return status happens.

Therefore, I would not suggest using your proposed solution.

You should add internal buffers into your hardware_interface, or even another thread to sync communication with your hardware.

I hope this helps you!

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2021-04-15 10:22:49 -0500

Seen: 521 times

Last updated: Nov 25 '21