Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes | List of all members
gazebo::GazeboRosDepthCamera Class Reference

#include <gazebo_ros_depth_camera.h>

Inheritance diagram for gazebo::GazeboRosDepthCamera:
Inheritance graph
[legend]

Public Member Functions

virtual void Advertise ()
 Advertise point cloud, depth image, normals and reflectance. More...
 
 GazeboRosDepthCamera ()
 Constructor. More...
 
virtual void Load (sensors::SensorPtr _parent, sdf::ElementPtr _sdf) override
 Load the plugin. More...
 
 ~GazeboRosDepthCamera ()
 Destructor. More...
 

Protected Member Functions

virtual void OnNewDepthFrame (const float *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format) override
 Update the controller. More...
 
virtual void OnNewImageFrame (const unsigned char *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format) override
 Update the controller. More...
 
virtual void OnNewRGBPointCloud (const float *_pcd, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format) override
 Update the controller. More...
 
virtual void PublishCameraInfo ()
 

Protected Attributes

ros::Publisher depth_image_camera_info_pub_
 

Private Member Functions

void DepthImageConnect ()
 
void DepthImageDisconnect ()
 
void DepthInfoConnect ()
 
void DepthInfoDisconnect ()
 
void FillDepthImage (const float *_src)
 push depth image data into ros topic More...
 
bool FillDepthImageHelper (sensor_msgs::Image &image_msg, uint32_t rows_arg, uint32_t cols_arg, uint32_t step_arg, void *data_arg)
 
bool FillPointCloudHelper (sensor_msgs::PointCloud2 &point_cloud_msg, uint32_t rows_arg, uint32_t cols_arg, uint32_t step_arg, void *data_arg)
 
void FillPointdCloud (const float *_src)
 Put camera data to the ROS topic. More...
 
void InfoConnect ()
 
void InfoDisconnect ()
 
void NormalsConnect ()
 Increase the counter which count the subscribers are connected. More...
 
void NormalsDisconnect ()
 Decrease the counter which count the subscribers are connected. More...
 
void PointCloudConnect ()
 
void PointCloudDisconnect ()
 
void PublishCameraInfo ()
 
void PublishCameraInfo (common::Time &last_update_time)
 
void PublishCameraInfo (ros::Publisher camera_info_publisher)
 Publish CameraInfo to the ROS topic. More...
 
void ReflectanceConnect ()
 Increase the counter which count the subscribers are connected. More...
 
void ReflectanceDisconnect ()
 Decrease the counter which count the subscribers are connected. More...
 
- Private Member Functions inherited from gazebo::GazeboRosCameraUtils
 GazeboRosCameraUtils ()
 Constructor. More...
 
void Load (sensors::SensorPtr _parent, sdf::ElementPtr _sdf, const std::string &_camera_name_suffix, double _hack_baseline)
 Load the plugin. More...
 
void Load (sensors::SensorPtr _parent, sdf::ElementPtr _sdf, const std::string &_camera_name_suffix="")
 Load the plugin. More...
 
event::ConnectionPtr OnLoad (const boost::function< void()> &)
 
 ~GazeboRosCameraUtils ()
 Destructor. More...
 
void CameraQueueThread ()
 
virtual bool CanTriggerCamera ()
 
void ImageConnect ()
 
void ImageDisconnect ()
 
void PublishCameraInfo ()
 
void PublishCameraInfo (common::Time &last_update_time)
 
void PublishCameraInfo (ros::Publisher camera_info_publisher)
 Publish CameraInfo to the ROS topic. More...
 
void PutCameraData (const unsigned char *_src)
 Put camera data to the ROS topic. More...
 
void PutCameraData (const unsigned char *_src, common::Time &last_update_time)
 
virtual void TriggerCamera ()
 

Private Attributes

std::string depth_image_camera_info_topic_name_
 
int depth_image_connect_count_
 Keep track of number of connctions for point clouds. More...
 
sensor_msgs::Image depth_image_msg_
 
ros::Publisher depth_image_pub_
 
std::string depth_image_topic_name_
 image where each pixel contains the depth information More...
 
int depth_info_connect_count_
 
common::Time depth_sensor_update_time_
 
common::Time last_depth_image_camera_info_update_time_
 
event::ConnectionPtr load_connection_
 
ros::Publisher normal_pub_
 
int normals_connect_count_
 Keep track of number of connections for normals. More...
 
std::string normals_topic_name_
 ROS normals topic name. More...
 
float * pcd_ = nullptr
 copy of the pointcloud data, used to place normals in the world More...
 
int point_cloud_connect_count_
 Keep track of number of connctions for point clouds. More...
 
double point_cloud_cutoff_
 
sensor_msgs::PointCloud2 point_cloud_msg_
 PointCloud2 point cloud message. More...
 
ros::Publisher point_cloud_pub_
 A pointer to the ROS node. A node will be instantiated if it does not exist. More...
 
std::string point_cloud_topic_name_
 ROS image topic name. More...
 
int reduce_normals_
 adding one value each reduce_normals_ to the array marker More...
 
int reflectance_connect_count_
 Keep track of number of connections for reflectance. More...
 
sensor_msgs::Image reflectance_msg_
 
ros::Publisher reflectance_pub_
 
std::string reflectance_topic_name_
 ROS reflectance topic name. More...
 
bool use_depth_image_16UC1_format_
 
- Private Attributes inherited from gazebo::GazeboRosCameraUtils
bool auto_distortion_
 
bool border_crop_
 
boost::thread callback_queue_thread_
 
rendering::CameraPtr camera_
 
boost::shared_ptr< camera_info_manager::CameraInfoManagercamera_info_manager_
 
ros::Publisher camera_info_pub_
 camera info More...
 
std::string camera_info_topic_name_
 
ros::CallbackQueue camera_queue_
 
double cx_
 
double cx_prime_
 
double cy_
 
unsigned int depth_
 
double distortion_k1_
 
double distortion_k2_
 
double distortion_k3_
 
double distortion_t1_
 
double distortion_t2_
 
double focal_length_
 
std::string format_
 
std::string frame_name_
 ROS frame transform name to use in the image message header. This should typically match the link name the sensor is attached. More...
 
double hack_baseline_
 
unsigned int height_
 
boost::shared_ptr< int > image_connect_count_
 Keep track of number of image connections. More...
 
boost::shared_ptr< boost::mutex > image_connect_count_lock_
 A mutex to lock access to image_connect_count_. More...
 
sensor_msgs::Image image_msg_
 ROS image message. More...
 
image_transport::Publisher image_pub_
 
std::string image_topic_name_
 ROS image topic name. More...
 
bool initialized_
 True if camera util is initialized. More...
 
common::Time last_info_update_time_
 
common::Time last_update_time_
 
boost::mutex lock_
 A mutex to lock access to fields that are used in ROS message callbacks. More...
 
sensors::SensorPtr parentSensor_
 
ros::NodeHandlerosnode_
 A pointer to the ROS node. A node will be instantiated if it does not exist. More...
 
common::Time sensor_update_time_
 
int skip_
 
std::string trigger_topic_name_
 ROS trigger topic name. More...
 
std::string type_
 size of image buffer More...
 
double update_period_
 
double update_rate_
 update rate of this sensor More...
 
boost::shared_ptr< bool > was_active_
 Keep track when we activate this camera through ros subscription, was it already active? resume state when unsubscribed. More...
 
unsigned int width_
 
physics::WorldPtr world
 
physics::WorldPtr world_
 

Detailed Description

Definition at line 62 of file gazebo_ros_depth_camera.h.

Constructor & Destructor Documentation

◆ GazeboRosDepthCamera()

gazebo::GazeboRosDepthCamera::GazeboRosDepthCamera ( )

Constructor.

Parameters
parentThe parent entity, must be a Model or a Sensor

Definition at line 49 of file gazebo_ros_depth_camera.cpp.

◆ ~GazeboRosDepthCamera()

gazebo::GazeboRosDepthCamera::~GazeboRosDepthCamera ( )

Destructor.

Definition at line 61 of file gazebo_ros_depth_camera.cpp.

Member Function Documentation

◆ Advertise()

void gazebo::GazeboRosDepthCamera::Advertise ( )
virtual

Advertise point cloud, depth image, normals and reflectance.

Definition at line 146 of file gazebo_ros_depth_camera.cpp.

◆ DepthImageConnect()

void gazebo::GazeboRosDepthCamera::DepthImageConnect ( )
private

Definition at line 250 of file gazebo_ros_depth_camera.cpp.

◆ DepthImageDisconnect()

void gazebo::GazeboRosDepthCamera::DepthImageDisconnect ( )
private

Definition at line 258 of file gazebo_ros_depth_camera.cpp.

◆ DepthInfoConnect()

void gazebo::GazeboRosDepthCamera::DepthInfoConnect ( )
private

Definition at line 265 of file gazebo_ros_depth_camera.cpp.

◆ DepthInfoDisconnect()

void gazebo::GazeboRosDepthCamera::DepthInfoDisconnect ( )
private

Definition at line 271 of file gazebo_ros_depth_camera.cpp.

◆ FillDepthImage()

void gazebo::GazeboRosDepthCamera::FillDepthImage ( const float *  _src)
private

push depth image data into ros topic

copy from depth to depth image message

Definition at line 605 of file gazebo_ros_depth_camera.cpp.

◆ FillDepthImageHelper()

bool gazebo::GazeboRosDepthCamera::FillDepthImageHelper ( sensor_msgs::Image &  image_msg,
uint32_t  rows_arg,
uint32_t  cols_arg,
uint32_t  step_arg,
void *  data_arg 
)
private

Definition at line 721 of file gazebo_ros_depth_camera.cpp.

◆ FillPointCloudHelper()

bool gazebo::GazeboRosDepthCamera::FillPointCloudHelper ( sensor_msgs::PointCloud2 &  point_cloud_msg,
uint32_t  rows_arg,
uint32_t  cols_arg,
uint32_t  step_arg,
void *  data_arg 
)
private

Definition at line 627 of file gazebo_ros_depth_camera.cpp.

◆ FillPointdCloud()

void gazebo::GazeboRosDepthCamera::FillPointdCloud ( const float *  _src)
private

Put camera data to the ROS topic.

copy from depth to point cloud message

Definition at line 580 of file gazebo_ros_depth_camera.cpp.

◆ InfoConnect()

void gazebo::GazeboRosDepthCamera::InfoConnect ( )
private

◆ InfoDisconnect()

void gazebo::GazeboRosDepthCamera::InfoDisconnect ( )
private

◆ Load()

void gazebo::GazeboRosDepthCamera::Load ( sensors::SensorPtr  _parent,
sdf::ElementPtr  _sdf 
)
overridevirtual

Load the plugin.

Parameters
takein SDF root element

Definition at line 71 of file gazebo_ros_depth_camera.cpp.

◆ NormalsConnect()

void gazebo::GazeboRosDepthCamera::NormalsConnect ( )
private

Increase the counter which count the subscribers are connected.

Definition at line 221 of file gazebo_ros_depth_camera.cpp.

◆ NormalsDisconnect()

void gazebo::GazeboRosDepthCamera::NormalsDisconnect ( )
private

Decrease the counter which count the subscribers are connected.

Definition at line 240 of file gazebo_ros_depth_camera.cpp.

◆ OnNewDepthFrame()

void gazebo::GazeboRosDepthCamera::OnNewDepthFrame ( const float *  _image,
unsigned int  _width,
unsigned int  _height,
unsigned int  _depth,
const std::string &  _format 
)
overrideprotectedvirtual

Update the controller.

Definition at line 278 of file gazebo_ros_depth_camera.cpp.

◆ OnNewImageFrame()

void gazebo::GazeboRosDepthCamera::OnNewImageFrame ( const unsigned char *  _image,
unsigned int  _width,
unsigned int  _height,
unsigned int  _depth,
const std::string &  _format 
)
overrideprotectedvirtual

Update the controller.

Definition at line 446 of file gazebo_ros_depth_camera.cpp.

◆ OnNewRGBPointCloud()

void gazebo::GazeboRosDepthCamera::OnNewRGBPointCloud ( const float *  _pcd,
unsigned int  _width,
unsigned int  _height,
unsigned int  _depth,
const std::string &  _format 
)
overrideprotectedvirtual

Update the controller.

Definition at line 331 of file gazebo_ros_depth_camera.cpp.

◆ PointCloudConnect()

void gazebo::GazeboRosDepthCamera::PointCloudConnect ( )
private

Definition at line 193 of file gazebo_ros_depth_camera.cpp.

◆ PointCloudDisconnect()

void gazebo::GazeboRosDepthCamera::PointCloudDisconnect ( )
private

Definition at line 202 of file gazebo_ros_depth_camera.cpp.

◆ PublishCameraInfo() [1/4]

void gazebo::GazeboRosCameraUtils::PublishCameraInfo
private

Definition at line 674 of file gazebo_ros_camera_utils.cpp.

◆ PublishCameraInfo() [2/4]

void gazebo::GazeboRosDepthCamera::PublishCameraInfo ( )
protectedvirtual

Definition at line 781 of file gazebo_ros_depth_camera.cpp.

◆ PublishCameraInfo() [3/4]

void gazebo::GazeboRosCameraUtils::PublishCameraInfo
private

Definition at line 665 of file gazebo_ros_camera_utils.cpp.

◆ PublishCameraInfo() [4/4]

void gazebo::GazeboRosCameraUtils::PublishCameraInfo
private

Publish CameraInfo to the ROS topic.

Definition at line 690 of file gazebo_ros_camera_utils.cpp.

◆ ReflectanceConnect()

void gazebo::GazeboRosDepthCamera::ReflectanceConnect ( )
private

Increase the counter which count the subscribers are connected.

Definition at line 212 of file gazebo_ros_depth_camera.cpp.

◆ ReflectanceDisconnect()

void gazebo::GazeboRosDepthCamera::ReflectanceDisconnect ( )
private

Decrease the counter which count the subscribers are connected.

Definition at line 230 of file gazebo_ros_depth_camera.cpp.

Member Data Documentation

◆ depth_image_camera_info_pub_

ros::Publisher gazebo::GazeboRosDepthCamera::depth_image_camera_info_pub_
protected

Definition at line 188 of file gazebo_ros_depth_camera.h.

◆ depth_image_camera_info_topic_name_

std::string gazebo::GazeboRosDepthCamera::depth_image_camera_info_topic_name_
private

Definition at line 180 of file gazebo_ros_depth_camera.h.

◆ depth_image_connect_count_

int gazebo::GazeboRosDepthCamera::depth_image_connect_count_
private

Keep track of number of connctions for point clouds.

Definition at line 131 of file gazebo_ros_depth_camera.h.

◆ depth_image_msg_

sensor_msgs::Image gazebo::GazeboRosDepthCamera::depth_image_msg_
private

Definition at line 152 of file gazebo_ros_depth_camera.h.

◆ depth_image_pub_

ros::Publisher gazebo::GazeboRosDepthCamera::depth_image_pub_
private

Definition at line 146 of file gazebo_ros_depth_camera.h.

◆ depth_image_topic_name_

std::string gazebo::GazeboRosDepthCamera::depth_image_topic_name_
private

image where each pixel contains the depth information

Definition at line 179 of file gazebo_ros_depth_camera.h.

◆ depth_info_connect_count_

int gazebo::GazeboRosDepthCamera::depth_info_connect_count_
private

Definition at line 181 of file gazebo_ros_depth_camera.h.

◆ depth_sensor_update_time_

common::Time gazebo::GazeboRosDepthCamera::depth_sensor_update_time_
private

Definition at line 187 of file gazebo_ros_depth_camera.h.

◆ last_depth_image_camera_info_update_time_

common::Time gazebo::GazeboRosDepthCamera::last_depth_image_camera_info_update_time_
private

Definition at line 134 of file gazebo_ros_depth_camera.h.

◆ load_connection_

event::ConnectionPtr gazebo::GazeboRosDepthCamera::load_connection_
private

Definition at line 190 of file gazebo_ros_depth_camera.h.

◆ normal_pub_

ros::Publisher gazebo::GazeboRosDepthCamera::normal_pub_
private

Definition at line 148 of file gazebo_ros_depth_camera.h.

◆ normals_connect_count_

int gazebo::GazeboRosDepthCamera::normals_connect_count_
private

Keep track of number of connections for normals.

Definition at line 124 of file gazebo_ros_depth_camera.h.

◆ normals_topic_name_

std::string gazebo::GazeboRosDepthCamera::normals_topic_name_
private

ROS normals topic name.

Definition at line 170 of file gazebo_ros_depth_camera.h.

◆ pcd_

float* gazebo::GazeboRosDepthCamera::pcd_ = nullptr
private

copy of the pointcloud data, used to place normals in the world

Definition at line 156 of file gazebo_ros_depth_camera.h.

◆ point_cloud_connect_count_

int gazebo::GazeboRosDepthCamera::point_cloud_connect_count_
private

Keep track of number of connctions for point clouds.

Definition at line 112 of file gazebo_ros_depth_camera.h.

◆ point_cloud_cutoff_

double gazebo::GazeboRosDepthCamera::point_cloud_cutoff_
private

Definition at line 158 of file gazebo_ros_depth_camera.h.

◆ point_cloud_msg_

sensor_msgs::PointCloud2 gazebo::GazeboRosDepthCamera::point_cloud_msg_
private

PointCloud2 point cloud message.

Definition at line 151 of file gazebo_ros_depth_camera.h.

◆ point_cloud_pub_

ros::Publisher gazebo::GazeboRosDepthCamera::point_cloud_pub_
private

A pointer to the ROS node. A node will be instantiated if it does not exist.

Definition at line 145 of file gazebo_ros_depth_camera.h.

◆ point_cloud_topic_name_

std::string gazebo::GazeboRosDepthCamera::point_cloud_topic_name_
private

ROS image topic name.

Definition at line 164 of file gazebo_ros_depth_camera.h.

◆ reduce_normals_

int gazebo::GazeboRosDepthCamera::reduce_normals_
private

adding one value each reduce_normals_ to the array marker

Definition at line 161 of file gazebo_ros_depth_camera.h.

◆ reflectance_connect_count_

int gazebo::GazeboRosDepthCamera::reflectance_connect_count_
private

Keep track of number of connections for reflectance.

Definition at line 117 of file gazebo_ros_depth_camera.h.

◆ reflectance_msg_

sensor_msgs::Image gazebo::GazeboRosDepthCamera::reflectance_msg_
private

Definition at line 153 of file gazebo_ros_depth_camera.h.

◆ reflectance_pub_

ros::Publisher gazebo::GazeboRosDepthCamera::reflectance_pub_
private

Definition at line 147 of file gazebo_ros_depth_camera.h.

◆ reflectance_topic_name_

std::string gazebo::GazeboRosDepthCamera::reflectance_topic_name_
private

ROS reflectance topic name.

Definition at line 167 of file gazebo_ros_depth_camera.h.

◆ use_depth_image_16UC1_format_

bool gazebo::GazeboRosDepthCamera::use_depth_image_16UC1_format_
private

Definition at line 184 of file gazebo_ros_depth_camera.h.


The documentation for this class was generated from the following files:


gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Nov 23 2023 03:50:28