Go to the documentation of this file.
28 #include "sensor_msgs/LaserScan.h"
32 #define DEG2RAD M_PI/180.0
34 int main(
int argc,
char **argv)
41 sensor_msgs::LaserScan scan_msg;
54 n.
param<std::string>(
"host", host,
"192.168.1.2");
55 n.
param<std::string>(
"frame_id", frame_id,
"laser");
56 n.
param<
bool>(
"publish_min_range_as_inf", inf_range,
false);
57 n.
param<
int>(
"port", port, 2111);
65 ROS_WARN(
"Unable to connect, retrying.");
78 ROS_WARN(
"Unable to get laser output range. Retrying.");
85 ROS_DEBUG(
"Laser configuration: scaningFrequency %d, angleResolution %d, startAngle %d, stopAngle %d",
87 ROS_DEBUG(
"Laser output range:angleResolution %d, startAngle %d, stopAngle %d",
90 scan_msg.header.frame_id = frame_id;
91 scan_msg.range_min = 0.01;
92 scan_msg.range_max = 20.0;
94 scan_msg.angle_increment =
static_cast<double>(
outputRange.angleResolution / 10000.0 *
DEG2RAD);
95 scan_msg.angle_min =
static_cast<double>(
outputRange.startAngle / 10000.0 *
DEG2RAD - M_PI / 2);
96 scan_msg.angle_max =
static_cast<double>(
outputRange.stopAngle / 10000.0 *
DEG2RAD - M_PI / 2);
102 int num_values = angle_range /
outputRange.angleResolution;
103 if (angle_range %
outputRange.angleResolution == 0)
108 scan_msg.ranges.resize(num_values);
109 scan_msg.intensities.resize(num_values);
111 scan_msg.time_increment =
116 ROS_DEBUG_STREAM(
"Time increment is " <<
static_cast<int>(scan_msg.time_increment * 1000000) <<
" microseconds");
126 ROS_DEBUG(
"Setting scan data configuration.");
141 ROS_WARN(
"Laser not ready. Retrying initialization.");
169 ROS_DEBUG(
"Commanding continuous measurements.");
176 scan_msg.header.stamp =
start;
177 ++scan_msg.header.seq;
185 float range_data = data.
dist1[i] * 0.001;
187 if (inf_range && range_data < scan_msg.range_min)
189 scan_msg.ranges[i] = std::numeric_limits<float>::infinity();
193 scan_msg.ranges[i] = range_data;
199 scan_msg.intensities[i] = data.
rssi1[i];
207 ROS_ERROR(
"Laser timed out on delivering scan, attempting to reinitialize.");
void login()
Log into LMS1xx unit. Increase privilege level, giving ability to change device configuration.
scanOutputRange getScanOutputRange() const
Get current output range configuration. Get output range configuration :
bool position
Position. Defines whether position values are output.
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
Structure containing single scan message.
void startDevice()
The device is returned to the measurement mode after configuration.
void stopMeas()
Stop measurements. After receiving this command LMS1xx unit stop spinning laser and measuring.
ROSCPP_DECL void spinOnce()
int main(int argc, char **argv)
bool deviceName
Device name. Determines whether the device name is to be output.
#define ROS_DEBUG_STREAM(args)
int outputChannel
Output channels. Defines which output channel is activated.
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
status_t queryStatus()
Get current status of LMS1xx device.
Structure containing scan output range configuration.
int dist_len1
Number of samples in dist1.
void disconnect()
Disconnect from LMS1xx device.
bool isConnected()
Get status of connection.
void startMeas()
Start measurements. After receiving this command LMS1xx unit starts spinning laser and measuring.
#define ROS_INFO_STREAM(args)
int angleResolution
Scanning resolution. 1/10000 degree.
Class responsible for communicating with LMS1xx device.
int startAngle
Start angle. 1/10000 degree.
uint16_t dist1[1082]
Radial distance for the first reflected pulse.
int scaningFrequency
Scanning frequency. 1/100 Hz.
int stopAngle
Stop angle. 1/10000 degree.
T param(const std::string ¶m_name, const T &default_val) const
int outputInterval
Output interval. Defines which scan is output.
int encoder
Encoders channels. Defines which output channel is activated.
uint16_t rssi1[1082]
Remission values for the first reflected pulse.
Structure containing scan data configuration.
int rssi_len1
Number of samples in rssi1.
void setScanDataCfg(const scanDataCfg &cfg)
Set scan data configuration. Set format of scan message returned by device.
scanCfg getScanCfg() const
Get current scan configuration. Get scan configuration :
void scanContinous(int start)
Start or stop continuous data acquisition. After reception of this command device start or stop conti...
bool remission
Remission. Defines whether remission values are output.
Structure containing scan configuration.
void connect(std::string host, int port=2111)
Connect to LMS1xx.
int resolution
Remission resolution. Defines whether the remission values are output with 8-bit or 16bit resolution.
bool getScanData(scanData *scan_data)
Receive single scan message.
lms1xx
Author(s): Konrad Banachowicz
autogenerated on Wed Mar 2 2022 00:28:01