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

prevent calling ros::init without name; use node_name command option instead of namespace #44

Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 2 additions & 1 deletion launch/naoqi_driver.launch
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,8 @@
<arg name="nao_ip" default="$(optenv NAO_IP)" />
<arg name="roscore_ip" default="127.0.0.1" />
<arg name="network_interface" default="eth0" />
<arg name="node_name" default="naoqi_driver" />

<node pkg="naoqi_driver" type="naoqi_driver_node" name="naoqi_driver" required="true" args="--qi-url=tcp://$(arg nao_ip):9559 --roscore_ip=$(arg roscore_ip) --network_interface=$(arg network_interface)" output="screen" />
<node pkg="naoqi_driver" type="naoqi_driver_node" name="$(arg node_name)" required="true" args="--qi-url=tcp://$(arg nao_ip):9559 --roscore_ip=$(arg roscore_ip) --network_interface=$(arg network_interface)" output="screen" />

</launch>
22 changes: 17 additions & 5 deletions src/external_registration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,15 @@
#include "naoqi_env.hpp"
#include "helpers/driver_helpers.hpp"

std::pair<std::string, std::string> ros_node_name_parser(const std::string& o) {
if(o.find("__name:=") == 0) {
return std::make_pair(std::string("node_name"), o.substr(std::string("__name:=").size()));
} else {
return std::make_pair(std::string(), std::string());
}
}


int main(int argc, char** argv)
{
/* adjust the SDK prefix in case you compiled via catkin*/
Expand All @@ -37,17 +46,20 @@ int main(int argc, char** argv)
ros::removeROSArgs( argc, argv, args_out );

namespace po = boost::program_options;
po::options_description desc("Options");
po::options_description desc("Options"), all_desc("Options");
desc.add_options()
("help,h", "print help message")
("roscore_ip,r", po::value<std::string>(), "set the ip of the roscore to use")
("network_interface,i", po::value<std::string>()->default_value("eth0"), "set the network interface over which to connect")
("namespace,n", po::value<std::string>()->default_value(""), "set an explicit namespace in case ROS namespace variables cannot be used");
("network_interface,i", po::value<std::string>()->default_value("eth0"), "set the network interface over which to connect");

all_desc.add_options()
("node_name,n", po::value<std::string>()->default_value("naoqi_driver"), "this node name");
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

no need for that line anymore right ?

all_desc.add(desc);

po::variables_map vm;
try
{
po::store( po::parse_command_line(argc, argv, desc), vm );
po::store( po::command_line_parser(argc, argv).options(all_desc).extra_parser(ros_node_name_parser).run(), vm );
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

No need to add a custom parse, ros::removeROSArgs( argc, argv, args_out ); already removes the __name argument

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@vrabaud We rather need to use __name than remove it to pass this value to naoqi::Driver.

}
catch (boost::program_options::invalid_command_line_syntax& e)
{
Expand All @@ -69,7 +81,7 @@ int main(int argc, char** argv)

// everything's correctly parsed - let's start the app!
app.start();
boost::shared_ptr<naoqi::Driver> bs = qi::import("naoqi_driver_module").call<qi::Object<naoqi::Driver> >("ROS-Driver", app.session(), vm["namespace"].as<std::string>()).asSharedPtr();
boost::shared_ptr<naoqi::Driver> bs = qi::import("naoqi_driver_module").call<qi::Object<naoqi::Driver> >("ROS-Driver", app.session(), vm["node_name"].as<std::string>()).asSharedPtr();
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Use args_out instead of vm to get the name.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

there is no node name information in args_out variable.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

oh right, as it is a default argument. How about using the proper ROS API then: http://docs.ros.org/jade/api/roscpp/html/namespaceros_1_1this__node.html

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@vrabaud You mean ros::this_node::getName? It is empty until called ros::init, because ros api has no way to know its node name before ros::init.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

yes, you're right, sorry.


app.session()->registerService("ROS-Driver", bs);

Expand Down
7 changes: 6 additions & 1 deletion src/ros_env.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -88,8 +88,13 @@ static void setMasterURI( const std::string& uri, const std::string& network_int
std::map< std::string, std::string > remap;
remap["__master"] = uri;
remap["__ip"] = ::naoqi::ros_env::getROSIP(network_interface);
std::string ros_node_name = ::naoqi::ros_env::getPrefix();
if (ros_node_name.empty()) {
std::cerr << "node_name can not be empty!!! please execute this node with `rosrun`/`roslaunch` or specify ROS node_name with --node_name=<name>" << std::endl;
exit(-1);
}
// init ros without a sigint-handler in order to shutdown correctly by naoqi
ros::init( remap, ::naoqi::ros_env::getPrefix(), ros::init_options::NoSigintHandler );
ros::init( remap, ros_node_name, ros::init_options::NoSigintHandler );
// to prevent shutdown based on no existing nodehandle
ros::start();

Expand Down