ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
The two ActionClients in skills.cpp are attempting to create NodeHandle's in their internal implementation: https://github.com/ros/actionlib/blob/hydro-devel/include/actionlib/client/action_client.h#L184
As those are global variables, they are constructed before main() is even run. You must delay the construction of these objects until after main() has executed. The easiest way is to make the global variables pointers, create a function which sets those global variables, and then call that function after main() has started.
actionlib::SimpleActionClient<rq3_proxy::rq3Action>* acRq3;;
actionlib::SimpleActionClient<ur5_proxy::ur5Action>* acUr5;("ur5Node", true);
void initActionClients()
{
acRq3 = new actionlib::SimpleActionClient("rq3proxynode", true);
acUr5 = new actionlib::SimpleActionClient("acUr5", true);
}
int main()
{
ros::init(argc, argv);
initActionClients();
//Be happy
}
2 | No.2 Revision |
The two ActionClients in skills.cpp are attempting to create NodeHandle's in their internal implementation: https://github.com/ros/actionlib/blob/hydro-devel/include/actionlib/client/action_client.h#L184
As those are global variables, they are constructed before main() is even run. You must delay the construction of these objects until after main() has executed. The easiest way is to make the global variables pointers, create a function which sets those global variables, and then call that function after main() has started.
actionlib::SimpleActionClient<rq3_proxy::rq3Action>* acRq3;;
acRq3;
actionlib::SimpleActionClient<ur5_proxy::ur5Action>* acUr5;("ur5Node", true);
acUr5;
void initActionClients()
{
acRq3 = new actionlib::SimpleActionClient("rq3proxynode", true);
acUr5 = new actionlib::SimpleActionClient("acUr5", true);
}
int main()
{
ros::init(argc, argv);
initActionClients();
//Be happy
}
3 | No.3 Revision |
The two ActionClients in skills.cpp are attempting to create NodeHandle's in their internal implementation: https://github.com/ros/actionlib/blob/hydro-devel/include/actionlib/client/action_client.h#L184
In the ROS C++ API (roscpp), you must always call ros::init before creating a NodeHandle.
As those are global variables, they are constructed before main() is even run. You must delay the construction of these objects until after main() has executed. The easiest way is to make the global variables pointers, create a function which sets those global variables, and then call that function after main() has started.
actionlib::SimpleActionClient<rq3_proxy::rq3Action>* acRq3;
actionlib::SimpleActionClient<ur5_proxy::ur5Action>* acUr5;
void initActionClients()
{
acRq3 = new actionlib::SimpleActionClient("rq3proxynode", true);
acUr5 = new actionlib::SimpleActionClient("acUr5", true);
}
int main()
{
ros::init(argc, argv);
initActionClients();
//Be happy
}
4 | No.4 Revision |
The two ActionClients in skills.cpp are attempting to create NodeHandle's NodeHandle objects in within their internal implementation:
https://github.com/ros/actionlib/blob/hydro-devel/include/actionlib/client/action_client.h#L184
In the ROS C++ API (roscpp), you must always call ros::init before creating a NodeHandle.
As those are global variables, they are constructed before main() is even run. You must delay the construction of these objects until after main() has executed. The easiest way is to make the global variables pointers, create a function which sets those global variables, and then call that function after main() has started.
actionlib::SimpleActionClient<rq3_proxy::rq3Action>* acRq3;
actionlib::SimpleActionClient<ur5_proxy::ur5Action>* acUr5;
void initActionClients()
{
acRq3 = new actionlib::SimpleActionClient("rq3proxynode", true);
acUr5 = new actionlib::SimpleActionClient("acUr5", true);
}
int main()
{
ros::init(argc, argv);
initActionClients();
//Be happy
}
5 | No.5 Revision |
The two ActionClients in skills.cpp are attempting to create NodeHandle objects in within their internal implementation:
https://github.com/ros/actionlib/blob/hydro-devel/include/actionlib/client/action_client.h#L184
In the ROS C++ API (roscpp), you must always call ros::init before creating a NodeHandle.
As those are global variables, they are constructed before main() is even run. You must delay the construction of these objects until after main() has executed. The easiest way is to make the global variables pointers, create a function which sets those global variables, and then call that function after main() has started.
actionlib::SimpleActionClient<rq3_proxy::rq3Action>* acRq3;
actionlib::SimpleActionClient<ur5_proxy::ur5Action>* acUr5;
void initActionClients()
{
acRq3 = new actionlib::SimpleActionClient("rq3proxynode", true);
acUr5 = new actionlib::SimpleActionClient("acUr5", true);
}
int main()
{
ros::init(argc, argv);
initActionClients();
//Be happy
}