Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

joint_traj_action: segfault (null pointer) in withinGoalConstraints() when no feedback has been received #85

Closed
gavanderhoorn opened this issue Oct 22, 2014 · 9 comments
Labels

Comments

@gavanderhoorn
Copy link
Member

While looking into Rename JOINT_NAMES in ur_driver test_move.py on ROS Answers:

I've observed that joint_trajectory_action::withinGoalConstraints(..) tries to dereference the last_trajectory_state_ member variable in a call to industrial_robot_client::utils::isWithinRange(..), even when no FollowJointTrajectoryFeedback has ever been received.

Sending a goal to the joint_trajectory_action node "too early" (ie: JointTrajectoryAction::controllerStateCB(..) has not been invoked) then results in a segfault.

Backtrace:

[1413970334.414501639] [ INFO] [/joint_trajectory_action]: Received new goal
joint_trajectory_action: /usr/include/boost/smart_ptr/shared_ptr.hpp:418: T* boost::shared_ptr<T>::operator->() const [with T = const control_msgs::FollowJointTrajectoryFeedback_<std::allocator<void> >]: Assertion `px != 0' failed.

Program received signal SIGABRT, Aborted.
0xb7fdf1b2 in ?? () from /lib/ld-linux.so.2
(gdb) bt
#0  0xb7fdf1b2 in ?? () from /lib/ld-linux.so.2
#1  0xb7a81e0f in raise () from /lib/i386-linux-gnu/libc.so.6
#2  0xb7a85455 in abort () from /lib/i386-linux-gnu/libc.so.6
#3  0xb7a7acb5 in ?? () from /lib/i386-linux-gnu/libc.so.6
#4  0xb7a7ad67 in __assert_fail () from /lib/i386-linux-gnu/libc.so.6
#5  0x080c7a6d in boost::shared_ptr<control_msgs::FollowJointTrajectoryFeedback_<std::allocator<void> > const>::operator-> (this=0xbfffe838)
    at /usr/include/boost/smart_ptr/shared_ptr.hpp:418
#6  0x080bf571 in industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::withinGoalConstraints (this=0xbfffe650, msg=..., traj=...)
    at /home/user/ros/answers_test_hydro/src/industrial_core/industrial_robot_client/src/joint_trajectory_action.cpp:293
#7  0x080bd1dc in industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::goalCB (this=0xbfffe650, gh=...)
    at /home/user/ros/answers_test_hydro/src/industrial_core/industrial_robot_client/src/joint_trajectory_action.cpp:132
#8  0x080d8db3 in boost::_mfi::mf1<void, industrial_robot_client::joint_trajectory_action::JointTrajectoryAction, actionlib::ServerGoalHandle<control_msgs::FollowJointTrajectoryAction_<std::allocator<void> > >&>::operator() (this=0xbfffe6f8, p=0xbfffe650, a1=...)
    at /usr/include/boost/bind/mem_fn_template.hpp:165
#9  0x080d738e in boost::_bi::list2<boost::_bi::value<industrial_robot_client::joint_trajectory_action::JointTrajectoryAction*>, boost::arg<1> >::operator()<boost::_mfi::mf1<void, industrial_robot_client::joint_trajectory_action::JointTrajectoryAction, actionlib::ServerGoalHandle<control_msgs::FollowJointTrajectoryAction_<std::allocator<void> > >&>, boost::_bi::list1<actionlib::ServerGoalHandle<control_msgs::FollowJointTrajectoryAction_<std::allocator<void> > >&> > (this=0xbfffe700, f=..., a=...) at /usr/include/boost/bind/bind.hpp:313
#10 0x080d4fb1 in boost::_bi::bind_t<void, boost::_mfi::mf1<void, industrial_robot_client::joint_trajectory_action::JointTrajectoryAction, actionlib::ServerGoalHandle<control_msgs::FollowJointTrajectoryAction_<std::allocator<void> > >&>, boost::_bi::list2<boost::_bi::value<industrial_robot_client::joint_trajectory_action::JointTrajectoryAction*>, boost::arg<1> > >::operator()<actionlib::ServerGoalHandle<control_msgs::FollowJointTrajectoryAction_<std::allocator<void> > > > (this=0xbfffe6f8, a1=...) at /usr/include/boost/bind/bind_template.hpp:32
#11 0x080d24ce in boost::detail::function::void_function_obj_invoker1<boost::_bi::bind_t<void, boost::_mfi::mf1<void, industrial_robot_client::joint_trajectory_action::JointTrajectoryAction, actionlib::ServerGoalHandle<control_msgs::FollowJointTrajectoryAction_<std::allocator<void> > >&>, boost::_bi::list2<boost::_bi::value<industrial_robot_client::joint_trajectory_action::JointTrajectoryAction*>, boost::arg<1> > >, void, actionlib::ServerGoalHandle<control_msgs::FollowJointTrajectoryAction_<std::allocator<void> > > >::invoke (function_obj_ptr=..., a0=...)
    at /usr/include/boost/function/function_template.hpp:153
#12 0x080d2cb4 in boost::function1<void, actionlib::ServerGoalHandle<control_msgs::FollowJointTrajectoryAction_<std::allocator<void> > > >::operator()
    (this=0xbfffe6f4, a0=...) at /usr/include/boost/function/function_template.hpp:1013
#13 0x080ceb32 in actionlib::ActionServerBase<control_msgs::FollowJointTrajectoryAction_<std::allocator<void> > >::goalCallback (this=0xbfffe694, 
    goal=...) at /opt/ros/hydro/include/actionlib/server/action_server_base.h:252
#14 0x080dd62e in boost::_mfi::mf1<void, actionlib::ActionServerBase<control_msgs::FollowJointTrajectoryAction_<std::allocator<void> > >, boost::shared_ptr<control_msgs::FollowJointTrajectoryActionGoal_<std::allocator<void> > const> const&>::call<actionlib::ActionServer<control_msgs::FollowJointTrajectoryAction_<std::allocator<void> > >*, boost::shared_ptr<control_msgs::FollowJointTrajectoryActionGoal_<std::allocator<void> > const> const> (
    this=0x8125b9c, u=@0x8125ba4: 0xbfffe694, b1=...) at /usr/include/boost/bind/mem_fn_template.hpp:156
#15 0x080dc515 in boost::_mfi::mf1<void, actionlib::ActionServerBase<control_msgs::FollowJointTrajectoryAction_<std::allocator<void> > >, boost::shared_ptr<control_msgs::FollowJointTrajectoryActionGoal_<std::allocator<void> > const> const&>::operator()<actionlib::ActionServer<control_msgs::FollowJointTrajectoryAction_<std::allocator<void> > >*> (this=0x8125b9c, u=@0x8125ba4: 0xbfffe694, a1=...) at /usr/include/boost/bind/mem_fn_template.hpp:171
#16 0x080da7c6 in boost::_bi::list2<boost::_bi::value<actionlib::ActionServer<control_msgs::FollowJointTrajectoryAction_<std::allocator<void> > >*>, boost::arg<1> >::operator()<boost::_mfi::mf1<void, actionlib::ActionServerBase<control_msgs::FollowJointTrajectoryAction_<std::allocator<void> > >, boost::shared_ptr<control_msgs::FollowJointTrajectoryActionGoal_<std::allocator<void> > const> const&>, boost::_bi::list1<boost::shared_ptr<control_msgs::FollowJointTrajectoryActionGoal_<std::allocator<void> > const> const&> > (this=0x8125ba4, f=..., a=...) at /usr/include/boost/bind/bind.hpp:313
#17 0x080d8f49 in boost::_bi::bind_t<void, boost::_mfi::mf1<void, actionlib::ActionServerBase<control_msgs::FollowJointTrajectoryAction_<std::allocator<void> > >, boost::shared_ptr<control_msgs::FollowJointTrajectoryActionGoal_<std::allocator<void> > const> const&>, boost::_bi::list2<boost::_bi::value<actionlib::ActionServer<control_msgs::FollowJointTrajectoryAction_<std::allocator<void> > >*>, boost::arg<1> > >::operator()<boost::shared_ptr<control_msgs::FollowJointTrajectoryActionGoal_<std::allocator<void> > const> > (this=0x8125b9c, a1=...) at /usr/include/boost/bind/bind_template.hpp:47
#18 0x080d7820 in boost::detail::function::void_function_obj_invoker1<boost::_bi::bind_t<void, boost::_mfi::mf1<void, actionlib::ActionServerBase<control_msgs::FollowJointTrajectoryAction_<std::allocator<void> > >, boost::shared_ptr<control_msgs::FollowJointTrajectoryActionGoal_<std::allocator<void> > const> const&>, boost::_bi::list2<boost::_bi::value<actionlib::ActionServer<control_msgs::FollowJointTrajectoryAction_<std::allocator<void> > >*>, boost::arg<1> > >, void, boost::shared_ptr<control_msgs::FollowJointTrajectoryActionGoal_<std::allocator<void> > const> const&>::invoke (
    function_obj_ptr=..., a0=...) at /usr/include/boost/function/function_template.hpp:153
#19 0x080dc79c in boost::function1<void, boost::shared_ptr<control_msgs::FollowJointTrajectoryActionGoal_<std::allocator<void> > const> const&>::operator() (this=0x8125b98, a0=...) at /usr/include/boost/function/function_template.hpp:1013
#20 0x080da92c in boost::detail::function::void_function_obj_invoker1<boost::function<void (boost::shared_ptr<control_msgs::FollowJointTrajectoryActionGoal_<std::allocator<void> > const> const&)>, void, boost::shared_ptr<control_msgs::FollowJointTrajectoryActionGoal_<std::allocator<void> > const> >::invoke(boost::detail::function::function_buffer&, boost::shared_ptr<control_msgs::FollowJointTrajectoryActionGoal_<std::allocator<void> > const>) (
    function_obj_ptr=..., a0=...) at /usr/include/boost/function/function_template.hpp:153
#21 0x080e1f66 in boost::function1<void, boost::shared_ptr<control_msgs::FollowJointTrajectoryActionGoal_<std::allocator<void> > const> >::operator() (
    this=0x8125a14, a0=...) at /usr/include/boost/function/function_template.hpp:1013
#22 0x080e01b7 in ros::SubscriptionCallbackHelperT<boost::shared_ptr<control_msgs::FollowJointTrajectoryActionGoal_<std::allocator<void> > const> const&, void>::call (this=0x8125a10, params=...) at /opt/ros/hydro/include/ros/subscription_callback_helper.h:140
#23 0xb7ea42b7 in ros::SubscriptionQueue::call() () from /opt/ros/hydro/lib/libroscpp.so
#24 0xb7e55297 in ros::CallbackQueue::callOneCB(ros::CallbackQueue::TLS*) () from /opt/ros/hydro/lib/libroscpp.so
#25 0xb7e56da4 in ros::CallbackQueue::callAvailable(ros::WallDuration) () from /opt/ros/hydro/lib/libroscpp.so
#26 0xb7ea7a78 in ros::SingleThreadedSpinner::spin(ros::CallbackQueue*) () from /opt/ros/hydro/lib/libroscpp.so
#27 0xb7e8c097 in ros::spin(ros::Spinner&) () from /opt/ros/hydro/lib/libroscpp.so
#28 0xb7e8c0c8 in ros::spin() () from /opt/ros/hydro/lib/libroscpp.so
#29 0x080bb1bb in industrial_robot_client::joint_trajectory_action::JointTrajectoryAction::run (this=0xbfffe650)
    at /home/user/ros/answers_test_hydro/src/industrial_core/industrial_robot_client/include/industrial_robot_client/joint_trajectory_action.h:67
#30 0x080babf2 in main (argc=1, argv=0xbfffe8f4)
    at /home/user/ros/answers_test_hydro/src/industrial_core/industrial_robot_client/src/generic_joint_trajectory_action_node.cpp:42
@gavanderhoorn
Copy link
Member Author

I'm not really sure if there is an obvious solution to this: if no feedback has been received, are all goals automatically not within bounds? Intuitively, I'd say we cannot know, but I don't see a way to express that using the Actionlib API / interfaces.

@gavanderhoorn
Copy link
Member Author

Also: this is not normally something you run into as in situations with an actual robot driver, joint states are received as soon as the driver starts. The first goals are then sent some time after system initialisation. In the case of the ROS Answers post, there are not joint states yet (no implementation of the robot state server on the controller), leading to the observed crash.

@shaun-edwards
Copy link
Member

Isn't there a way to reject a goal? This could be done if no feedback has been received (with a proper error message).

@gavanderhoorn
Copy link
Member Author

On 22-10-2014 17:24, Shaun Edwards wrote:

Isn't there a way to reject a goal? This could be done if no feedback has been received (with a proper error message).

yes, that would be an option indeed.

@RosBort
Copy link

RosBort commented Oct 23, 2014

What does it mean to reject a goal?

@gavanderhoorn
Copy link
Member Author

What does it mean to reject a goal?

An ActionServer can reject a goal if it decides that it cannot complete the client's request. Rejecting is different from aborting, as the latter can only be done with a Goal that has already been accepted (and is either active or preempted). See wiki/actionlib/DetailedDescription - Server Transitions and wiki/actionlib/DetailedDescription - result topic: Goal information upon completion for more information.

In this particular case the joint_trajectory_action node would check whether it has ever received any feedback, and if that is not the case, immediately Reject all incoming goals. Without feedback, the server cannot determine whether a goal has been reached, as it cannot compare desired vs actual states.

@gavanderhoorn
Copy link
Member Author

@RosBort: can you try my issue85_within_constraints_segfault branch? As far as I can tell, that should fix the issue.

You won't be able to send any goals to your simple_message server as long as you don't also send joint_states back.

@RosBort
Copy link

RosBort commented Oct 23, 2014

I tried it on my work station and it works. That means it throws the error: "Waiting for server feedback".
I yet don't know how to use the branch, but I just reinstalled the industrial_core via GIT and copied the change into the joint_trajectory_action.cpp.

@gavanderhoorn
Copy link
Member Author

That's the intended behaviour. Thanks.

shaun-edwards added a commit that referenced this issue Oct 28, 2014
…segfault

Fix for issue #85: reject all goals until feedback has been received
Jmeyer1292 pushed a commit to Jmeyer1292/industrial_core that referenced this issue Feb 14, 2017
…link

Updated link to Indigo training materail
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Development

No branches or pull requests

3 participants