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

ros control assertion failed

asked 2018-06-15 07:52:59 -0600

venkisagunner gravatar image

updated 2018-06-15 09:16:07 -0600

I wrote a custom controller for my robot. I used ros control boilerplate (by dave coleman) for hardware interface. The code compiles but I get the following error.

myrobot_hw_main: /opt/ros/lunar/include/hardware_interface/posvel_command_interface.h:72: void hardware_interface::PosVelJointHandle::setCommandVelocity(double): Assertion `cmd_vel_' failed.
[myrobot/myrobot_hardware_interface-1] process has died [pid 96416, exit code -6, cmd /home/user/catkin_ws/devel/lib/control_pkg/myrobot_hw_main __name:=myrobot_hardware_interface __log:=/home/user/.ros/log/aee6bd46-702a-11e8-82d2-000c29ad2621/myrobot-myrobot_hardware_interface-1.log].
log file: /home/user/.ros/log/aee6bd46-702a-11e8-82d2-000c29ad2621/myrobot-myrobot_hardware_interface-1*.log

I wrote a controller for omni drive and if I understand it properly, this is where the problem is. I used this interface called PosVelJointInterface from posvel_command_interface.h. The problem occurs when I executed the following lines. Basically in my controller, I take in the twist command, do some math and generate four velocities which I'm trying to populate using the setCommandVelocity method.

hardware_interface::PosVelJointHandle wheel_1;    
wheel_1.setCommandVelocity(wheelVelocities.velocity[0]);
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
2

answered 2018-06-18 01:59:04 -0600

gvdhoorn gravatar image

updated 2018-06-18 02:00:03 -0600

According to the sources (here), cmd_vel_ is a pointer to a double that gets initialised in the ctor (here).

The code you show ("The problem occurs when I executed the following lines") doesn't initialise the PosVelJointHandle properly (or at least: it doesn't provide any values for the arguments), it's using this ctor, which sets all pointers to 0. If you then try to use setCommandVelocity(..), the assert is triggered.

Two comments:

  1. if you're writing a controller, why are you intantiating hardware_interface classes directly? Shouldn't that be the responsibility of your / a hardware_interface implementation for your robot?
  2. read up / find examples of how to initialise a PosVelJointHandle correctly and update your code (if you have determined you really should be intantiating those classes yourself.
edit flag offensive delete link more

Comments

I realised the mistake and solved the problem. Forgot to close the issue. My apologies. Thank you for taking your time in helping me out here.

venkisagunner gravatar image venkisagunner  ( 2018-06-18 10:15:00 -0600 )edit

Could you help future readers by describing how you eventually solved your problem?

gvdhoorn gravatar image gvdhoorn  ( 2018-06-18 10:18:31 -0600 )edit

I found a way here. This is available in ROS controllers git repo. Instead of using a PosVelJointHandle, I used the JointHandle and JointStateInterface ..

venkisagunner gravatar image venkisagunner  ( 2018-06-18 10:21:19 -0600 )edit

And integrating that with the boilerplate was trivial. In my previous approach, I declared the joint handles but didnt call the getHandle (line 319) method which resulted in no resource allocation. When I ran rosrun controller_manager controller_manager myrobot/list_controllers, I found no resources

venkisagunner gravatar image venkisagunner  ( 2018-06-18 10:23:55 -0600 )edit

Question Tools

2 followers

Stats

Asked: 2018-06-15 07:52:59 -0600

Seen: 469 times

Last updated: Jun 18 '18