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

feat(*): migrate to ros2 humble #20

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
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
10 changes: 5 additions & 5 deletions launch/ydlidar_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -36,16 +36,16 @@ def generate_launch_description():
description='FPath to the ROS2 parameters file to use.')

driver_node = LifecycleNode(package='ydlidar_ros2_driver',
node_executable='ydlidar_ros2_driver_node',
node_name='ydlidar_ros2_driver_node',
executable='ydlidar_ros2_driver_node',
name='ydlidar_ros2_driver_node',
output='screen',
emulate_tty=True,
parameters=[parameter_file],
node_namespace='/',
namespace='/',
)
tf2_node = Node(package='tf2_ros',
node_executable='static_transform_publisher',
node_name='static_tf_pub_laser',
executable='static_transform_publisher',
name='static_tf_pub_laser',
arguments=['0', '0', '0.02','0', '0', '0', '1','base_link','laser_frame'],
)

Expand Down
14 changes: 7 additions & 7 deletions launch/ydlidar_launch_view.py
Original file line number Diff line number Diff line change
Expand Up @@ -37,21 +37,21 @@ def generate_launch_description():
description='FPath to the ROS2 parameters file to use.')

driver_node = LifecycleNode(package='ydlidar_ros2_driver',
node_executable='ydlidar_ros2_driver_node',
node_name='ydlidar_ros2_driver_node',
executable='ydlidar_ros2_driver_node',
name='ydlidar_ros2_driver_node',
output='screen',
emulate_tty=True,
parameters=[parameter_file],
node_namespace='/',
namespace='/',
)
tf2_node = Node(package='tf2_ros',
node_executable='static_transform_publisher',
node_name='static_tf_pub_laser',
executable='static_transform_publisher',
name='static_tf_pub_laser',
arguments=['0', '0', '0.02','0', '0', '0', '1','base_link','laser_frame'],
)
rviz2_node = Node(package='rviz2',
node_executable='rviz2',
node_name='rviz2',
executable='rviz2',
name='rviz2',
arguments=['-d', rviz_config_file],
)

Expand Down
6 changes: 3 additions & 3 deletions params/ydlidar.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -4,11 +4,11 @@ ydlidar_ros2_driver_node:
frame_id: laser_frame
ignore_array: ""
baudrate: 230400
lidar_type: 1
device_type: 0
lidar_type: 1 # 0:TYPE_TOF, 1:TYPE_TRIANGLE 2:TYPE_TOF_NET
device_type: 0 # 0:YDLIDAR_TYPE_SERIAL, 1:YDLIDAR_TYPE_TCP
sample_rate: 9
abnormal_check_count: 4
resolution_fixed: true
fixed_resolution: true
reversion: true
inverted: true
auto_reconnect: true
Expand Down
44 changes: 22 additions & 22 deletions src/ydlidar_ros2_driver_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,112 +41,112 @@ int main(int argc, char *argv[]) {

CYdLidar laser;
std::string str_optvalue = "/dev/ydlidar";
node->declare_parameter("port");
node->declare_parameter<std::string>("port");
node->get_parameter("port", str_optvalue);
///lidar port
laser.setlidaropt(LidarPropSerialPort, str_optvalue.c_str(), str_optvalue.size());

///ignore array
str_optvalue = "";
node->declare_parameter("ignore_array");
node->declare_parameter<std::string>("ignore_array");
node->get_parameter("ignore_array", str_optvalue);
laser.setlidaropt(LidarPropIgnoreArray, str_optvalue.c_str(), str_optvalue.size());

std::string frame_id = "laser_frame";
node->declare_parameter("frame_id");
node->declare_parameter<std::string>("frame_id");
node->get_parameter("frame_id", frame_id);

//////////////////////int property/////////////////
/// lidar baudrate
int optval = 230400;
node->declare_parameter("baudrate");
node->declare_parameter<int>("baudrate");
node->get_parameter("baudrate", optval);
laser.setlidaropt(LidarPropSerialBaudrate, &optval, sizeof(int));
/// tof lidar
optval = TYPE_TRIANGLE;
node->declare_parameter("lidar_type");
node->declare_parameter<int>("lidar_type");
node->get_parameter("lidar_type", optval);
laser.setlidaropt(LidarPropLidarType, &optval, sizeof(int));
/// device type
optval = YDLIDAR_TYPE_SERIAL;
node->declare_parameter("device_type");
node->declare_parameter<int>("device_type");
node->get_parameter("device_type", optval);
laser.setlidaropt(LidarPropDeviceType, &optval, sizeof(int));
/// sample rate
optval = 9;
node->declare_parameter("sample_rate");
node->declare_parameter<int>("sample_rate");
node->get_parameter("sample_rate", optval);
laser.setlidaropt(LidarPropSampleRate, &optval, sizeof(int));
/// abnormal count
optval = 4;
node->declare_parameter("abnormal_check_count");
node->declare_parameter<int>("abnormal_check_count");
node->get_parameter("abnormal_check_count", optval);
laser.setlidaropt(LidarPropAbnormalCheckCount, &optval, sizeof(int));


//////////////////////bool property/////////////////
/// fixed angle resolution
bool b_optvalue = false;
node->declare_parameter("fixed_resolution");
node->declare_parameter<bool>("fixed_resolution");
node->get_parameter("fixed_resolution", b_optvalue);
laser.setlidaropt(LidarPropFixedResolution, &b_optvalue, sizeof(bool));
/// rotate 180
b_optvalue = true;
node->declare_parameter("reversion");
node->declare_parameter<bool>("reversion");
node->get_parameter("reversion", b_optvalue);
laser.setlidaropt(LidarPropReversion, &b_optvalue, sizeof(bool));
/// Counterclockwise
b_optvalue = true;
node->declare_parameter("inverted");
node->declare_parameter<bool>("inverted");
node->get_parameter("inverted", b_optvalue);
laser.setlidaropt(LidarPropInverted, &b_optvalue, sizeof(bool));
b_optvalue = true;
node->declare_parameter("auto_reconnect");
node->declare_parameter<bool>("auto_reconnect");
node->get_parameter("auto_reconnect", b_optvalue);
laser.setlidaropt(LidarPropAutoReconnect, &b_optvalue, sizeof(bool));
/// one-way communication
b_optvalue = false;
node->declare_parameter("isSingleChannel");
node->declare_parameter<bool>("isSingleChannel");
node->get_parameter("isSingleChannel", b_optvalue);
laser.setlidaropt(LidarPropSingleChannel, &b_optvalue, sizeof(bool));
/// intensity
b_optvalue = false;
node->declare_parameter("intensity");
node->declare_parameter<bool>("intensity");
node->get_parameter("intensity", b_optvalue);
laser.setlidaropt(LidarPropIntenstiy, &b_optvalue, sizeof(bool));
/// Motor DTR
b_optvalue = false;
node->declare_parameter("support_motor_dtr");
node->declare_parameter<bool>("support_motor_dtr");
node->get_parameter("support_motor_dtr", b_optvalue);
laser.setlidaropt(LidarPropSupportMotorDtrCtrl, &b_optvalue, sizeof(bool));

//////////////////////float property/////////////////
/// unit: °
float f_optvalue = 180.0f;
node->declare_parameter("angle_max");
node->declare_parameter<float>("angle_max");
node->get_parameter("angle_max", f_optvalue);
laser.setlidaropt(LidarPropMaxAngle, &f_optvalue, sizeof(float));
f_optvalue = -180.0f;
node->declare_parameter("angle_min");
node->declare_parameter<float>("angle_min");
node->get_parameter("angle_min", f_optvalue);
laser.setlidaropt(LidarPropMinAngle, &f_optvalue, sizeof(float));
/// unit: m
f_optvalue = 64.f;
node->declare_parameter("range_max");
node->declare_parameter<float>("range_max");
node->get_parameter("range_max", f_optvalue);
laser.setlidaropt(LidarPropMaxRange, &f_optvalue, sizeof(float));
f_optvalue = 0.1f;
node->declare_parameter("range_min");
node->declare_parameter<float>("range_min");
node->get_parameter("range_min", f_optvalue);
laser.setlidaropt(LidarPropMinRange, &f_optvalue, sizeof(float));
/// unit: Hz
f_optvalue = 10.f;
node->declare_parameter("frequency");
node->declare_parameter<float>("frequency");
node->get_parameter("frequency", f_optvalue);
laser.setlidaropt(LidarPropScanFrequency, &f_optvalue, sizeof(float));

bool invalid_range_is_inf = false;
node->declare_parameter("invalid_range_is_inf");
node->declare_parameter<bool>("invalid_range_is_inf");
node->get_parameter("invalid_range_is_inf", invalid_range_is_inf);


Expand All @@ -157,7 +157,7 @@ int main(int argc, char *argv[]) {
RCLCPP_ERROR(node->get_logger(), "%s\n", laser.DescribeError());
}

auto laser_pub = node->create_publisher<sensor_msgs::msg::LaserScan>("scan", rclcpp::SensorDataQoS());
auto laser_pub = node->create_publisher<sensor_msgs::msg::LaserScan>("scan", rclcpp::QoS(rclcpp::SensorDataQoS()));

auto stop_scan_service =
[&laser](const std::shared_ptr<rmw_request_id_t> request_header,
Expand Down