31 #include <dynamic_reconfigure/server.h>
32 #include "l3cam_ros/RgbConfig.h"
35 #include <beamagine.h>
36 #include <beamErrors.h>
38 #include "l3cam_ros/GetSensorsAvailable.h"
39 #include "l3cam_ros/ChangeRgbCameraBrightness.h"
40 #include "l3cam_ros/ChangeRgbCameraContrast.h"
41 #include "l3cam_ros/ChangeRgbCameraSaturation.h"
42 #include "l3cam_ros/ChangeRgbCameraSharpness.h"
43 #include "l3cam_ros/ChangeRgbCameraGamma.h"
44 #include "l3cam_ros/ChangeRgbCameraGain.h"
45 #include "l3cam_ros/EnableRgbCameraAutoWhiteBalance.h"
46 #include "l3cam_ros/ChangeRgbCameraWhiteBalance.h"
47 #include "l3cam_ros/EnableRgbCameraAutoExposureTime.h"
48 #include "l3cam_ros/ChangeRgbCameraExposureTime.h"
49 #include "l3cam_ros/ChangeStreamingProtocol.h"
50 #include "l3cam_ros/GetRtspPipeline.h"
52 #include "l3cam_ros/SensorDisconnected.h"
63 client_get_sensors_ = serviceClient<l3cam_ros::GetSensorsAvailable>(
"/L3Cam/l3cam_ros_node/get_sensors_available");
64 client_brightness_ = serviceClient<l3cam_ros::ChangeRgbCameraBrightness>(
"/L3Cam/l3cam_ros_node/change_rgb_brightness");
65 client_contrast_ = serviceClient<l3cam_ros::ChangeRgbCameraContrast>(
"/L3Cam/l3cam_ros_node/change_rgb_contrast");
66 client_saturation_ = serviceClient<l3cam_ros::ChangeRgbCameraSaturation>(
"/L3Cam/l3cam_ros_node/change_rgb_saturation");
67 client_sharpness_ = serviceClient<l3cam_ros::ChangeRgbCameraSharpness>(
"/L3Cam/l3cam_ros_node/change_rgb_sharpness");
68 client_gamma_ = serviceClient<l3cam_ros::ChangeRgbCameraGamma>(
"/L3Cam/l3cam_ros_node/change_rgb_gamma");
69 client_gain_ = serviceClient<l3cam_ros::ChangeRgbCameraGain>(
"/L3Cam/l3cam_ros_node/change_rgb_gain");
71 client_white_balance_ = serviceClient<l3cam_ros::ChangeRgbCameraWhiteBalance>(
"/L3Cam/l3cam_ros_node/change_rgb_white_balance");
73 client_exposure_time_ = serviceClient<l3cam_ros::ChangeRgbCameraExposureTime>(
"/L3Cam/l3cam_ros_node/change_rgb_exposure_time");
90 server_ =
new dynamic_reconfigure::Server<l3cam_ros::RgbConfig>;
111 template <
typename T>
112 void loadParam(
const std::string ¶m_name, T ¶m_var,
const T &default_val)
114 std::string full_param_name;
118 if (!
getParam(full_param_name, param_var))
126 param_var = default_val;
236 int error = L3CAM_OK;
256 config.rgb_rtsp_pipeline =
"";
263 config.rgb_rtsp_pipeline =
"";
273 int error = L3CAM_OK;
332 int error = L3CAM_OK;
361 int error = L3CAM_OK;
390 int error = L3CAM_OK;
419 int error = L3CAM_OK;
448 int error = L3CAM_OK;
477 int error = L3CAM_OK;
479 srv_gain_.request.gain = config.rgb_gain;
506 int error = L3CAM_OK;
535 int error = L3CAM_OK;
572 int error = L3CAM_OK;
601 int error = L3CAM_OK;
638 int error = L3CAM_OK;
691 dynamic_reconfigure::Server<l3cam_ros::RgbConfig> *
server_;
740 int main(
int argc,
char **argv)
742 ros::init(argc, argv,
"rgb_configuration");
748 if (!
node->client_get_sensors_.waitForExistence(timeout_duration))
754 int error = L3CAM_OK;
755 bool sensor_is_available =
false;
757 if (
node->client_get_sensors_.call(
node->srv_get_sensors_))
759 error =
node->srv_get_sensors_.response.error;
763 for (
int i = 0; i <
node->srv_get_sensors_.response.num_sensors; ++i)
765 if (
node->srv_get_sensors_.response.sensors[i].sensor_type == sensor_econ_rgb &&
node->srv_get_sensors_.response.sensors[i].sensor_available)
767 sensor_is_available =
true;
783 if (sensor_is_available)
785 ROS_INFO(
"RGB configuration is available");
792 node->setDynamicReconfigure();