example_rplidar_echoer_node.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2018, Andreas Gustavsson.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *
34 * Author: Andreas Gustavsson
35 *********************************************************************/
36 
37 #include <ros/ros.h>
38 #include <sensor_msgs/LaserScan.h>
39 
41 sensor_msgs::LaserScan msg_dummy;
42 sensor_msgs::LaserScan::ConstPtr msg_old(new sensor_msgs::LaserScan(msg_dummy));
43 
44 void cb(const sensor_msgs::LaserScan::ConstPtr & msg_org)
45 {
46  if (msg_old->header.stamp == msg_org->header.stamp)
47  {
48  return;
49  }
50 
51  msg_old = msg_org;
52  sensor_msgs::LaserScan msg = *msg_org;
53  msg.header.stamp = ros::Time::now();
54  unsigned int size = msg.ranges.size();
55 // for (unsigned int i=0; i<size; ++i)
56 // {
57 // if (msg.ranges[i] == std::numeric_limits<float>::infinity())
58 // {
59 // msg.ranges[i] = msg.range_max + 10.0;
60 // // msg.ranges[i] = 2;
61 // // msg.intensities[i] = 1000;
62 // }
63 // else if (msg.ranges[i] == -std::numeric_limits<float>::infinity())
64 // {
65 // msg.ranges[i] = msg.range_min - 10.0;
66 // // msg.ranges[i] = 2;
67 // // msg.intensities[i] = 1000;
68 // }
69 // }
70 
71  pub.publish(msg);
72 }
73 
74 int main(int argc, char** argv)
75 {
76  ros::init(argc, argv, "rplidar_laserscan_echoer");
78 
79  // Wait for time to become valid
81 
82  pub = n.advertise<sensor_msgs::LaserScan>("/lidar/scan_echoed", 10);
83  ros::Subscriber sub = n.subscribe<sensor_msgs::LaserScan>("/lidar/scan", 10, cb);
84 
85  ros::spin();
86 
87  return 0;
88 }
sensor_msgs::LaserScan msg_dummy
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL void spin(Spinner &spinner)
void cb(const sensor_msgs::LaserScan::ConstPtr &msg_org)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
static Time now()
int main(int argc, char **argv)
static bool waitForValid()
sensor_msgs::LaserScan::ConstPtr msg_old(new sensor_msgs::LaserScan(msg_dummy))
ros::Publisher pub


find_moving_objects
Author(s): Andreas Gustavsson
autogenerated on Mon Jun 10 2019 13:13:19