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

Fix node name empty related to pepper_robot issue #35 #85

Merged
merged 2 commits into from
Apr 12, 2017
Merged
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 @@ -4,7 +4,8 @@
<arg name="nao_port" default="$(optenv NAO_PORT 9559)" />
<arg name="roscore_ip" default="127.0.0.1" />
<arg name="network_interface" default="eth0" />
<arg name="namespace" default="naoqi_driver" />

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

</launch>
2 changes: 1 addition & 1 deletion src/external_registration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ int main(int argc, char** argv)
("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");
("namespace,n", po::value<std::string>()->default_value("naoqi_driver_node"), "set an explicit namespace in case ROS namespace variables cannot be used");

po::variables_map vm;
try
Expand Down
17 changes: 12 additions & 5 deletions src/naoqi_driver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -124,7 +124,14 @@ Driver::Driver( qi::SessionPtr session, const std::string& prefix )
recorder_(boost::make_shared<recorder::GlobalRecorder>(prefix)),
buffer_duration_(helpers::recorder::bufferDefaultDuration)
{
naoqi::ros_env::setPrefix(prefix);
if(prefix == ""){
std::cout << "Error driver prefix must not be empty" << std::endl;
throw new ros::Exception("Error driver prefix must not be empty");
}
else {
naoqi::ros_env::setPrefix(prefix);
}

}

Driver::~Driver()
Expand Down Expand Up @@ -577,10 +584,10 @@ void Driver::registerDefaultConverter()

bool sonar_enabled = boot_config_.get( "converters.sonar.enabled", true);
size_t sonar_frequency = boot_config_.get( "converters.sonar.frequency", 10);

bool odom_enabled = boot_config_.get( "converters.odom.enabled", true);
size_t odom_frequency = boot_config_.get( "converters.odom.frequency", 10);

bool bumper_enabled = boot_config_.get( "converters.bumper.enabled", true);
bool hand_enabled = boot_config_.get( "converters.touch_hand.enabled", true);
bool head_enabled = boot_config_.get( "converters.touch_head.enabled", true);
Expand Down Expand Up @@ -826,7 +833,7 @@ void Driver::registerDefaultConverter()
event_map_.find("head_touch")->second.isPublishing(true);
}
}

/** Odom */
if ( odom_enabled )
{
Expand All @@ -838,7 +845,7 @@ void Driver::registerDefaultConverter()
lc->registerCallback( message_actions::LOG, boost::bind(&recorder::BasicRecorder<nav_msgs::Odometry>::bufferize, lr, _1) );
registerConverter( lc, lp, lr );
}

}


Expand Down
2 changes: 1 addition & 1 deletion src/ros_env.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -90,7 +90,7 @@ static void setMasterURI( const std::string& uri, const std::string& network_int
remap["__ip"] = ::naoqi::ros_env::getROSIP(network_interface);
// init ros without a sigint-handler in order to shutdown correctly by naoqi
const char* ns_env = std::getenv("ROS_NAMESPACE");
ros::init( remap, (ns_env==NULL)?(std::string("naoqi_driver_node")):(::naoqi::ros_env::getPrefix()) , ros::init_options::NoSigintHandler );
ros::init( remap, (::naoqi::ros_env::getPrefix()), ros::init_options::NoSigintHandler );
// to prevent shutdown based on no existing nodehandle
ros::start();

Expand Down