- changed status to resolved
runKDL and runNLOPT don't return a value.
Hi there,
Sometimes when we launch:
roslaunch trac_ik_examples pr2_arm.launch
the program crashes when program reachROS_INFO_STREAM("*** Testing TRAC-IK with
This is or setup:
-
Ubuntu 14.04 and ROS indigo-devel.
-
Using catkin tools with clan++3.9 or g++ 4.8.4
-
We tried both master and kinetic-devel branches of trac_ik
Looking the code, we saw that runKDL
and runNLOPT
don't return a value, when they are suppose to. if I set the return value:
inline bool TRAC_IK::runKDL(const KDL::JntArray &q_init, const KDL::Frame &p_in)
{
return runSolver( *iksolver.get(), *nl_solver.get(), q_init, p_in);
}
instead of
inline bool TRAC_IK::runKDL(const KDL::JntArray &q_init, const KDL::Frame &p_in)
{
runSolver( *iksolver.get(), *nl_solver.get(), q_init, p_in);
}
in both runKDL
and runNLOPT
methods, the example ik_tests.cpp
works fine.
I'm not sure why this crash issue happens to me and not to you. I might miss something, especially because I have not work that much with boost synchronization mechanisms, but I think that if both methods are suppose to return something, it should be added.
thanks!
Comments (2)
-
Account Deactivated -
reporter great! thanks to you!
- Log in to comment
Thanks for the catch. This was just recently introduced from a user's pull request. I fixed this in the HEAD and even pushed for ros binaries to be updated.