Go to the documentation of this file. 1 #ifndef _ASTRA_ROS_ROS_DEVICE_HPP_
2 #define _ASTRA_ROS_ROS_DEVICE_HPP_
7 #include <dynamic_reconfigure/server.h>
10 #include "astra_ros/DeviceConfig.h"
12 #include "astra_ros/BodyFrame.h"
14 #include "astra_ros/GetChipId.h"
15 #include "astra_ros/GetDepthRegistration.h"
16 #include "astra_ros/GetImageStreamMode.h"
17 #include "astra_ros/GetImageStreamModes.h"
18 #include "astra_ros/GetIrExposure.h"
19 #include "astra_ros/GetIrGain.h"
20 #include "astra_ros/GetMirrored.h"
21 #include "astra_ros/GetRunning.h"
22 #include "astra_ros/GetSerial.h"
23 #include "astra_ros/GetUsbInfo.h"
24 #include "astra_ros/SetDepthRegistration.h"
25 #include "astra_ros/SetImageStreamMode.h"
26 #include "astra_ros/SetIrExposure.h"
27 #include "astra_ros/SetIrGain.h"
28 #include "astra_ros/SetMirrored.h"
29 #include "astra_ros/SetRunning.h"
50 const std::string &
getName()
const noexcept;
64 bool onGetChipId(GetChipId::Request &req, GetChipId::Response &res);
72 bool onGetIrExposure(GetIrExposure::Request &req, GetIrExposure::Response &res);
73 bool onGetIrGain(GetIrGain::Request &req, GetIrGain::Response &res);
76 bool onGetIrMirrored(GetMirrored::Request &req, GetMirrored::Response &res);
79 bool onGetIrRunning(GetRunning::Request &req, GetRunning::Response &res);
80 bool onGetSerial(GetSerial::Request &req, GetSerial::Response &res);
83 bool onGetIrUsbInfo(GetUsbInfo::Request &req, GetUsbInfo::Response &res);
88 bool onSetIrExposure(SetIrExposure::Request &req, SetIrExposure::Response &res);
89 bool onSetIrGain(SetIrGain::Request &req, SetIrGain::Response &res);
92 bool onSetIrMirrored(SetMirrored::Request &req, SetMirrored::Response &res);
95 bool onSetIrRunning(SetRunning::Request &req, SetRunning::Response &res);
107 std::unique_ptr<boost::recursive_mutex>
mut_;
std::shared_ptr< Device > Ptr
bool onSetDepthRegistration(SetDepthRegistration::Request &req, SetDepthRegistration::Response &res)
bool onSetColorImageStreamMode(SetImageStreamMode::Request &req, SetImageStreamMode::Response &res)
bool onSetIrExposure(SetIrExposure::Request &req, SetIrExposure::Response &res)
ros::ServiceServer get_depth_image_stream_mode_svc_
bool onGetIrUsbInfo(GetUsbInfo::Request &req, GetUsbInfo::Response &res)
bool onSetColorMirrored(SetMirrored::Request &req, SetMirrored::Response &res)
void onFrame(const Device::Frame &frame)
image_transport::ImageTransport image_transport_
bool onGetDepthRunning(GetRunning::Request &req, GetRunning::Response &res)
ros::ServiceServer get_ir_running_svc_
ros::ServiceServer set_ir_gain_svc_
bool onGetColorMirrored(GetMirrored::Request &req, GetMirrored::Response &res)
const std::string & getName() const noexcept
ros::ServiceServer get_depth_mirrored_svc_
orbbec_camera_params camera_parameters_
image_transport::Publisher colorized_body_image_pub_
ros::ServiceServer set_ir_running_svc_
bool onGetIrMirrored(GetMirrored::Request &req, GetMirrored::Response &res)
ros::ServiceServer set_ir_exposure_svc_
bool onGetColorUsbInfo(GetUsbInfo::Request &req, GetUsbInfo::Response &res)
ros::ServiceServer set_depth_mirrored_svc_
bool onGetDepthUsbInfo(GetUsbInfo::Request &req, GetUsbInfo::Response &res)
bool onGetDepthRegistration(GetDepthRegistration::Request &req, GetDepthRegistration::Response &res)
ros::ServiceServer get_color_running_svc_
ros::ServiceServer set_ir_mirrored_svc_
bool onSetColorRunning(SetRunning::Request &req, SetRunning::Response &res)
image_transport::Publisher masked_color_image_pub_
ros::ServiceServer get_ir_image_stream_mode_svc_
bool onGetColorImageStreamModes(GetImageStreamModes::Request &req, GetImageStreamModes::Response &res)
ros::ServiceServer get_serial_svc_
image_transport::Publisher depth_image_pub_
ros::ServiceServer get_ir_mirrored_svc_
bool publish_body_markers
bool onGetIrExposure(GetIrExposure::Request &req, GetIrExposure::Response &res)
std::unique_ptr< tf2_ros::TransformBroadcaster > tf_broadcaster_
ros::ServiceServer set_color_image_stream_mode_svc_
ros::Publisher color_camera_info_pub_
ros::Publisher body_frame_pub_
bool onGetSerial(GetSerial::Request &req, GetSerial::Response &res)
bool onGetIrGain(GetIrGain::Request &req, GetIrGain::Response &res)
bool onGetColorImageStreamMode(GetImageStreamMode::Request &req, GetImageStreamMode::Response &res)
ros::ServiceServer get_ir_usb_info_svc_
ros::ServiceServer set_color_running_svc_
image_transport::Publisher color_image_pub_
dynamic_reconfigure::Server< DeviceConfig > DeviceConfigServer
ros::Publisher point_cloud_pub_
bool onGetIrImageStreamMode(GetImageStreamMode::Request &req, GetImageStreamMode::Response &res)
bool onGetColorRunning(GetRunning::Request &req, GetRunning::Response &res)
ros::ServiceServer set_ir_image_stream_mode_svc_
const std::string DEVICE_NAMESPACE
ros::ServiceServer get_ir_exposure_svc_
std::string body_frame_id
ros::ServiceServer set_depth_registration_svc_
bool onGetChipId(GetChipId::Request &req, GetChipId::Response &res)
bool onGetDepthImageStreamModes(GetImageStreamModes::Request &req, GetImageStreamModes::Response &res)
image_transport::Publisher body_mask_image_pub_
ros::Publisher body_markers_pub_
bool onSetIrGain(SetIrGain::Request &req, SetIrGain::Response &res)
ros::ServiceServer get_depth_running_svc_
ros::ServiceServer get_color_usb_info_svc_
bool onSetDepthRunning(SetRunning::Request &req, SetRunning::Response &res)
void onDynamicReconfigure(DeviceConfig &config, uint32_t level)
ros::ServiceServer get_color_image_stream_modes_svc_
std::unique_ptr< DeviceConfigServer > dynamic_reconfigure_server_
ros::Publisher depth_camera_info_pub_
ros::ServiceServer get_depth_usb_info_svc_
ros::ServiceServer set_color_mirrored_svc_
bool onSetIrImageStreamMode(SetImageStreamMode::Request &req, SetImageStreamMode::Response &res)
bool onSetDepthMirrored(SetMirrored::Request &req, SetMirrored::Response &res)
ros::ServiceServer get_ir_image_stream_modes_svc_
ros::NodeHandle device_nh_
bool onGetIrRunning(GetRunning::Request &req, GetRunning::Response &res)
ros::ServiceServer get_chip_id_svc_
bool onGetDepthMirrored(GetMirrored::Request &req, GetMirrored::Response &res)
static Device::Configuration getConfiguration(ros::NodeHandle &nh)
bool onSetDepthImageStreamMode(SetImageStreamMode::Request &req, SetImageStreamMode::Response &res)
bool onSetIrRunning(SetRunning::Request &req, SetRunning::Response &res)
image_transport::Publisher ir_image_pub_
ros::ServiceServer get_color_mirrored_svc_
bool onGetIrImageStreamModes(GetImageStreamModes::Request &req, GetImageStreamModes::Response &res)
ros::ServiceServer get_depth_image_stream_modes_svc_
ros::ServiceServer get_ir_gain_svc_
RosDevice(const std::string &name, ros::NodeHandle &nh, ros::NodeHandle &pnh)
ros::ServiceServer set_depth_running_svc_
bool onGetDepthImageStreamMode(GetImageStreamMode::Request &req, GetImageStreamMode::Response &res)
std::unique_ptr< boost::recursive_mutex > mut_
ros::ServiceServer get_color_image_stream_mode_svc_
ros::ServiceServer set_depth_image_stream_mode_svc_
bool onSetIrMirrored(SetMirrored::Request &req, SetMirrored::Response &res)
image_transport::Publisher floor_mask_image_pub_
ros::ServiceServer get_depth_registration_svc_
astra_ros
Author(s): Braden McDorman
autogenerated on Wed Mar 2 2022 00:53:06