Skip to content

Commit

Permalink
Fixed Issue #2. Use a private namespace for the parameters.
Browse files Browse the repository at this point in the history
  • Loading branch information
romainreignier committed Jul 3, 2015
1 parent a88cd0b commit 7ea1c1c
Show file tree
Hide file tree
Showing 2 changed files with 7 additions and 6 deletions.
2 changes: 1 addition & 1 deletion package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package>
<name>rtimulib_ros</name>
<version>1.0.0</version>
<version>1.1.0</version>
<description>A simple package to use the nice RTIMULib from RichardsTech in ROS</description>

<author email="[email protected]">Romain REIGNIER</author>
Expand Down
11 changes: 6 additions & 5 deletions src/rtimulib_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,36 +33,37 @@ int main(int argc, char **argv)
ros::init(argc, argv, "rtimulib_node");
ROS_INFO("Imu driver is now running");
ros::NodeHandle n;
ros::NodeHandle private_n("~");

std::string topic_name;
if(!n.getParam("/rtimulib_node/topic_name", topic_name))
if(!private_n.getParam("topic_name", topic_name))
{
ROS_WARN("No topic_name provided - default: imu/data");
topic_name = "imu/data";
}

std::string calibration_file_path;
if(!n.getParam("/rtimulib_node/calibration_file_path", calibration_file_path))
if(!private_n.getParam("calibration_file_path", calibration_file_path))
{
ROS_ERROR("The calibration_file_path parameter must be set to use a calibration file.");
}

std::string calibration_file_name;
if(!n.getParam("/rtimulib_node/calibration_file_name", calibration_file_name))
if(!private_n.getParam("calibration_file_name", calibration_file_name))
{
ROS_WARN("No calibration_file_name provided - default: RTIMULib.ini");
calibration_file_name = "RTIMULib";
}

std::string frame_id;
if(!n.getParam("/rtimulib_node/frame_id", frame_id))
if(!private_n.getParam("frame_id", frame_id))
{
ROS_WARN("No frame_id provided - default: imu_link");
frame_id = "imu_link";
}

double update_rate;
if(!n.getParam("/rtimulib_node/update_rate", update_rate))
if(!private_n.getParam("update_rate", update_rate))
{
ROS_WARN("No update_rate provided - default: 20 Hz");
update_rate = 20;
Expand Down

0 comments on commit 7ea1c1c

Please sign in to comment.