39 #include "sensor_msgs/LaserScan.h" 41 #define RAD2DEG(x) ((x)*180./M_PI) 45 int count = scan->scan_time / scan->time_increment;
46 ROS_INFO(
"I heard a laser scan %s[%d]:", scan->header.frame_id.c_str(), count);
49 for(
int i = 0; i < count; i++) {
50 float degree =
RAD2DEG(scan->angle_min + scan->angle_increment * i);
51 ROS_INFO(
": [%f, %f]", degree, scan->ranges[i]);
55 int main(
int argc,
char **argv)
57 ros::init(argc, argv,
"rplidar_node_client");
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void scanCallback(const sensor_msgs::LaserScan::ConstPtr &scan)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)