38 #include <sensor_msgs/LaserScan.h> 42 sensor_msgs::LaserScan::ConstPtr
msg_old(
new sensor_msgs::LaserScan(
msg_dummy));
44 void cb(
const sensor_msgs::LaserScan::ConstPtr & msg_org)
46 if (
msg_old->header.stamp == msg_org->header.stamp)
52 sensor_msgs::LaserScan msg = *msg_org;
54 unsigned int size = msg.ranges.size();
74 int main(
int argc,
char** argv)
76 ros::init(argc, argv,
"rplidar_laserscan_echoer");
82 pub = n.
advertise<sensor_msgs::LaserScan>(
"/lidar/scan_echoed", 10);
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)
int main(int argc, char **argv)
static bool waitForValid()
sensor_msgs::LaserScan::ConstPtr msg_old(new sensor_msgs::LaserScan(msg_dummy))