Skip to content

Commit

Permalink
cob_sick_lms1xx: add range configuration
Browse files Browse the repository at this point in the history
  • Loading branch information
Shin-nn committed Sep 1, 2016
1 parent ce9c078 commit 695b55d
Showing 1 changed file with 8 additions and 2 deletions.
10 changes: 8 additions & 2 deletions cob_sick_lms1xx/ros/src/lms1xx_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,8 @@ class SickLMS1xxNode
double resolution;
double frequency;
bool set_config;
double min_range;
double max_range;
};

SickLMS1xxNode::SickLMS1xxNode()
Expand All @@ -74,6 +76,10 @@ SickLMS1xxNode::SickLMS1xxNode()
nh.param<double>("scan_frequency", frequency, 25);
if(!nh.hasParam("set_config")) ROS_WARN("Used default parameter for set_config");
nh.param<bool>("set_config", set_config, false);
if(!nh.hasParam("min_range")) ROS_WARN("Used default parameter for min_range");
nh.param<double>("min_range", min_range, 0.01);
if(!nh.hasParam("max_range")) ROS_WARN("Used default parameter for max_range");
nh.param<double>("max_range", max_range, 20.0);

ROS_INFO("connecting to laser at : %s", host.c_str());
ROS_INFO("using frame_id : %s", frame_id.c_str());
Expand Down Expand Up @@ -142,8 +148,8 @@ bool SickLMS1xxNode::initalizeMessage()
//init scan msg
scan_msg.header.frame_id = frame_id;

scan_msg.range_min = 0.01;
scan_msg.range_max = 20.0;
scan_msg.range_min = min_range;
scan_msg.range_max = max_range;

scan_msg.scan_time = 100.0/cfg.scaningFrequency;

Expand Down

0 comments on commit 695b55d

Please sign in to comment.