Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix obsolete code in rplidar_node_client #1

Open
wants to merge 1 commit into
base: ros2
Choose a base branch
from
Open
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
47 changes: 30 additions & 17 deletions src/client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,31 +35,44 @@
*/


#include <rclcpp/rclcpp.hpp>
#include <sensor_msgs/msg/laser_scan.hpp>
#include <memory>

#define ROS_INFO RCUTILS_LOG_INFO
#include "rclcpp/rclcpp.hpp"
#include <sensor_msgs/msg/laser_scan.hpp>
using std::placeholders::_1;

#define M_PI 3.1415926535897932384626433832795
#define RAD2DEG(x) ((x)*180./M_PI)

void scanCallback(const std::shared_ptr<sensor_msgs::msg::LaserScan> scan)
class RplidarNodeClient : public rclcpp::Node
{
int count = scan->scan_time / scan->time_increment;
ROS_INFO("I heard a laser scan %s[%d]:", scan->header.frame_id.c_str(), count);
ROS_INFO("angle_range, %f, %f", RAD2DEG(scan->angle_min), RAD2DEG(scan->angle_max));
public:
RplidarNodeClient()
: Node("rplidar_node_client")
{
subscription_ = this->create_subscription<sensor_msgs::msg::LaserScan>(
"scan/", 10, std::bind(&RplidarNodeClient::scan_callback, this, _1));
}

for(int i = 0; i < count; i++) {
float degree = RAD2DEG(scan->angle_min + scan->angle_increment * i);
ROS_INFO(": [%f, %f]", degree, scan->ranges[i]);
private:
void scan_callback(const sensor_msgs::msg::LaserScan::SharedPtr scan) const
{
int count = scan->scan_time / scan->time_increment;
RCLCPP_INFO(this->get_logger(), "I heard a laser scan %s[%d]:", scan->header.frame_id.c_str(), count);
RCLCPP_INFO(this->get_logger(), "angle_range, %f, %f", RAD2DEG(scan->angle_min), RAD2DEG(scan->angle_max));

for(int i = 0; i < count; i++) {
float degree = RAD2DEG(scan->angle_min + scan->angle_increment * i);
RCLCPP_INFO(this->get_logger(), ": [%f, %f]", degree, scan->ranges[i]);
}
}
}
rclcpp::Subscription<sensor_msgs::msg::LaserScan>::SharedPtr subscription_;
};

int main(int argc, char **argv)
int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
auto node = rclcpp::Node::make_shared("rplidar_node_client");
auto sub = node->create_subscription<sensor_msgs::msg::LaserScan>("/scan", scanCallback);
rclcpp::spin(node);
return 0;
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<RplidarNodeClient>());
rclcpp::shutdown();
return 0;
}