31 #include <dynamic_reconfigure/server.h>
32 #include "l3cam_ros/LidarConfig.h"
35 #include <beamagine.h>
36 #include <beamErrors.h>
38 #include "l3cam_ros/GetSensorsAvailable.h"
39 #include "l3cam_ros/ChangePointcloudColor.h"
40 #include "l3cam_ros/ChangePointcloudColorRange.h"
41 #include "l3cam_ros/ChangeDistanceRange.h"
42 #include "l3cam_ros/SetBiasShortRange.h"
43 #include "l3cam_ros/EnableAutoBias.h"
44 #include "l3cam_ros/ChangeBiasValue.h"
45 #include "l3cam_ros/ChangeAutobiasValue.h"
46 #include "l3cam_ros/ChangeStreamingProtocol.h"
47 #include "l3cam_ros/GetRtspPipeline.h"
49 #include "l3cam_ros/SensorDisconnected.h"
61 client_get_sensors_ = serviceClient<l3cam_ros::GetSensorsAvailable>(
"/L3Cam/l3cam_ros_node/get_sensors_available");
62 client_color_ = serviceClient<l3cam_ros::ChangePointcloudColor>(
"/L3Cam/l3cam_ros_node/change_pointcloud_color");
63 client_color_range_ = serviceClient<l3cam_ros::ChangePointcloudColorRange>(
"/L3Cam/l3cam_ros_node/change_pointcloud_color_range");
64 client_distance_range_ = serviceClient<l3cam_ros::ChangeDistanceRange>(
"/L3Cam/l3cam_ros_node/change_distance_range");
65 client_bias_short_range_ = serviceClient<l3cam_ros::SetBiasShortRange>(
"/L3Cam/l3cam_ros_node/set_bias_short_range");
66 client_auto_bias_ = serviceClient<l3cam_ros::EnableAutoBias>(
"/L3Cam/l3cam_ros_node/enable_auto_bias");
67 client_bias_value_ = serviceClient<l3cam_ros::ChangeBiasValue>(
"/L3Cam/l3cam_ros_node/change_bias_value");
68 client_autobias_value_ = serviceClient<l3cam_ros::ChangeAutobiasValue>(
"/L3Cam/l3cam_ros_node/change_autobias_value");
85 server_ =
new dynamic_reconfigure::Server<l3cam_ros::LidarConfig>;
106 template <
typename T>
107 void loadParam(
const std::string ¶m_name, T ¶m_var,
const T &default_val)
109 std::string full_param_name;
113 if (!
getParam(full_param_name, param_var))
121 param_var = default_val;
240 int error = L3CAM_OK;
260 config.lidar_rtsp_pipeline =
"";
267 config.lidar_rtsp_pipeline =
"";
277 int error = L3CAM_OK;
339 int error = L3CAM_OK;
341 srv_color_.request.visualization_color = config.pointcloud_color;
368 int error = L3CAM_OK;
401 int error = L3CAM_OK;
434 int error = L3CAM_OK;
463 int error = L3CAM_OK;
492 int error = L3CAM_OK;
522 int error = L3CAM_OK;
552 int error = L3CAM_OK;
582 int error = L3CAM_OK;
612 int error = L3CAM_OK;
665 dynamic_reconfigure::Server<l3cam_ros::LidarConfig> *
server_;
709 int main(
int argc,
char **argv)
711 ros::init(argc, argv,
"lidar_configuration");
717 if (!
node->client_get_sensors_.waitForExistence(timeout_duration))
723 int error = L3CAM_OK;
724 bool sensor_is_available =
false;
726 if (
node->client_get_sensors_.call(
node->srv_get_sensors_))
728 error =
node->srv_get_sensors_.response.error;
732 for (
int i = 0; i <
node->srv_get_sensors_.response.num_sensors; ++i)
734 if (
node->srv_get_sensors_.response.sensors[i].sensor_type == sensor_lidar &&
node->srv_get_sensors_.response.sensors[i].sensor_available)
736 sensor_is_available =
true;
752 if (sensor_is_available)
754 ROS_INFO(
"LiDAR configuration is available");
761 node->setDynamicReconfigure();