13 #include "sensor_msgs/LaserScan.h" 16 #define DEG2RAD(x) ((x)*M_PI/180.) 23 uint32_t n_range_values,
unsigned int *intensity_values,
24 uint32_t n_intensity_values,
ros::Time start,
25 double scan_time,
bool inverted,
float angle_min,
26 float angle_max, std::string frame_id)
28 static int scan_count = 0;
29 sensor_msgs::LaserScan scan_msg;
30 scan_msg.header.frame_id = frame_id;
33 scan_msg.angle_min = angle_max;
34 scan_msg.angle_max = angle_min;
36 scan_msg.angle_min = angle_min;
37 scan_msg.angle_max = angle_max;
39 scan_msg.angle_increment = (scan_msg.angle_max - scan_msg.angle_min) / (
double)(n_range_values-1);
40 scan_msg.scan_time = scan_time;
41 scan_msg.time_increment = scan_time / n_range_values;
42 scan_msg.range_min = 0.5;
43 scan_msg.range_max = 250.;
44 scan_msg.ranges.resize(n_range_values);
45 scan_msg.header.stamp = start;
46 for (
size_t i = 0; i < n_range_values; i++) {
47 scan_msg.ranges[i] = (float)range_values[i];
49 scan_msg.intensities.resize(n_intensity_values);
50 for (
size_t i = 0; i < n_intensity_values; i++) {
51 scan_msg.intensities[i] = (float)intensity_values[i];
68 time_smoothing_factor = 0.95;
69 error_threshold = .50;
73 time_smoothing_factor = smoothing_factor;
77 error_threshold = err_threshold;
80 if (smoothtime_prev.
is_zero() ==
true) {
81 smoothed_timestamp = recv_timestamp;
83 smoothed_timestamp = smoothtime_prev + expctd_dur;
84 double err = (recv_timestamp - smoothed_timestamp).toSec();
85 double time_error_threshold = expctd_dur.
toSec() * error_threshold;
86 if ((time_smoothing_factor > 0) && (fabs(err) < time_error_threshold)){
88 smoothed_timestamp += correction;
91 smoothed_timestamp = recv_timestamp;
94 smoothtime_prev = smoothed_timestamp;
95 return smoothed_timestamp;
106 this->max_len = max_len;
111 if (deq.size() > max_len) {
117 return sum/deq.size();
122 int main(
int argc,
char *argv[]) {
125 std::string ipaddress;
126 std::string frame_id;
128 int sick_motor_speed = 5;
129 double sick_step_angle = 1.5;
130 double active_sector_start_angle = 0;
131 double active_sector_stop_angle = 300;
132 double smoothing_factor, error_threshold;
138 nh_ns.
param(
"inverted", inverted,
false);
139 nh_ns.
param<std::string>(
"frame_id", frame_id,
"laser");
140 nh_ns.
param(
"timer_smoothing_factor", smoothing_factor, 0.97);
141 nh_ns.
param(
"timer_error_threshold", error_threshold, 0.5);
142 nh_ns.
param(
"resolution", sick_step_angle, 1.0);
143 nh_ns.
param(
"start_angle", active_sector_start_angle, 0.);
144 nh_ns.
param(
"stop_angle", active_sector_stop_angle, 300.);
145 nh_ns.
param(
"scan_rate", sick_motor_speed, 10);
147 double range_values[SickLD::SICK_MAX_NUM_MEASUREMENTS] = {0};
148 unsigned int intensity_values[SickLD::SICK_MAX_NUM_MEASUREMENTS] = {0};
150 unsigned int num_measurements = {0};
151 unsigned int sector_start_timestamp = {0};
152 unsigned int sector_stop_timestamp = {0};
153 double sector_step_angle = {0};
154 double sector_start_angle = {0};
155 double sector_stop_angle = {0};
165 &active_sector_start_angle,
166 &active_sector_stop_angle,
177 unsigned int last_sector_stop_timestamp = 0;
178 double full_duration;
189 §or_start_timestamp,
190 §or_stop_timestamp
194 double scan_duration = (sector_stop_timestamp - sector_start_timestamp) * 1e-3;
195 avg_scandur.
add_new(scan_duration);
196 scan_duration = avg_scandur.
get_mean();
198 if (last_sector_stop_timestamp == 0) {
199 full_duration = 1./((double)sick_motor_speed);
201 full_duration = (sector_stop_timestamp - last_sector_stop_timestamp) * 1e-3;
203 avg_fulldur.
add_new(full_duration);
204 full_duration = avg_fulldur.
get_mean();
209 publish_scan(&scan_pub, range_values, num_measurements, intensity_values,
210 num_measurements, start_scan_time, scan_duration, inverted,
211 DEG2RAD((
float)sector_start_angle),
DEG2RAD((
float)sector_stop_angle), frame_id);
214 <<
" smoothed start T: " << start_scan_time
215 <<
" smoothed rate: " << 1./(start_scan_time - last_start_scan_time).toSec()
216 <<
" raw start T: " << sector_start_timestamp
217 <<
" raw stop T: " << sector_stop_timestamp
218 <<
" dur: " << full_duration
219 <<
" step A: " << sector_step_angle
220 <<
" start A: " << sector_start_angle
221 <<
" stop A: " << sector_stop_angle);
222 last_start_scan_time = start_scan_time;
223 last_sector_stop_timestamp = sector_stop_timestamp;
void set_smoothing_factor(double smoothing_factor)
Between 0 and 1, bigger is smoother.
ros::Time smoothtime_prev
void publish_scan(ros::Publisher *pub, double *range_values, uint32_t n_range_values, unsigned int *intensity_values, uint32_t n_intensity_values, ros::Time start, double scan_time, bool inverted, float angle_min, float angle_max, std::string frame_id)
double time_smoothing_factor
void publish(const boost::shared_ptr< M > &message) const
ros::Time smooth_timestamp(ros::Time recv_timestamp, ros::Duration expctd_dur)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char *argv[])
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void set_error_threshold(double err_threshold)
Between 0 and 1, threshold on jitter acceptability, higher accepts more jitter before discarding...
#define DEFAULT_SICK_IP_ADDRESS
#define ROS_DEBUG_STREAM(args)
void add_new(double data)
#define DEFAULT_SICK_TCP_PORT
ROSCPP_DECL void spinOnce()