#include <gazebo_ros_depth_camera.h>
Public Member Functions | |
virtual void | Advertise () |
Advertise point cloud and depth image. | |
GazeboRosDepthCamera () | |
Constructor. | |
virtual void | Load (sensors::SensorPtr _parent, sdf::ElementPtr _sdf) |
Load the plugin. | |
~GazeboRosDepthCamera () | |
Destructor. | |
Protected Member Functions | |
virtual void | OnNewDepthFrame (const float *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format) |
Update the controller. | |
virtual void | OnNewImageFrame (const unsigned char *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format) |
Update the controller. | |
virtual void | OnNewRGBPointCloud (const float *_pcd, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format) |
Update the controller. | |
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 | |
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. | |
void | InfoConnect () |
Keep track of number of connctions for CameraInfo. | |
void | InfoDisconnect () |
void | PointCloudConnect () |
void | PointCloudDisconnect () |
Private Attributes | |
std::string | depth_image_camera_info_topic_name_ |
int | depth_image_connect_count_ |
Keep track of number of connctions for point clouds. | |
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 | |
int | depth_info_connect_count_ |
common::Time | depth_sensor_update_time_ |
common::Time | last_depth_image_camera_info_update_time_ |
event::ConnectionPtr | load_connection_ |
int | point_cloud_connect_count_ |
Keep track of number of connctions for point clouds. | |
double | point_cloud_cutoff_ |
sensor_msgs::PointCloud2 | point_cloud_msg_ |
PCL point cloud message. | |
ros::Publisher | point_cloud_pub_ |
A pointer to the ROS node. A node will be instantiated if it does not exist. | |
std::string | point_cloud_topic_name_ |
ROS image topic name. |
Definition at line 62 of file gazebo_ros_depth_camera.h.
Constructor.
parent | The parent entity, must be a Model or a Sensor |
Definition at line 45 of file gazebo_ros_depth_camera.cpp.
Destructor.
Definition at line 54 of file gazebo_ros_depth_camera.cpp.
void gazebo::GazeboRosDepthCamera::Advertise | ( | ) | [virtual] |
Advertise point cloud and depth image.
Definition at line 112 of file gazebo_ros_depth_camera.cpp.
void gazebo::GazeboRosDepthCamera::DepthImageConnect | ( | ) | [private] |
Definition at line 160 of file gazebo_ros_depth_camera.cpp.
void gazebo::GazeboRosDepthCamera::DepthImageDisconnect | ( | ) | [private] |
Definition at line 167 of file gazebo_ros_depth_camera.cpp.
void gazebo::GazeboRosDepthCamera::DepthInfoConnect | ( | ) | [private] |
Definition at line 174 of file gazebo_ros_depth_camera.cpp.
void gazebo::GazeboRosDepthCamera::DepthInfoDisconnect | ( | ) | [private] |
Definition at line 180 of file gazebo_ros_depth_camera.cpp.
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 337 of file gazebo_ros_depth_camera.cpp.
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 442 of file gazebo_ros_depth_camera.cpp.
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 359 of file gazebo_ros_depth_camera.cpp.
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 312 of file gazebo_ros_depth_camera.cpp.
void gazebo::GazeboRosDepthCamera::InfoConnect | ( | ) | [private] |
Keep track of number of connctions for CameraInfo.
Reimplemented from gazebo::GazeboRosCameraUtils.
void gazebo::GazeboRosDepthCamera::InfoDisconnect | ( | ) | [private] |
Reimplemented from gazebo::GazeboRosCameraUtils.
void gazebo::GazeboRosDepthCamera::Load | ( | sensors::SensorPtr | _parent, |
sdf::ElementPtr | _sdf | ||
) | [virtual] |
Load the plugin.
take | in SDF root element |
Definition at line 60 of file gazebo_ros_depth_camera.cpp.
void gazebo::GazeboRosDepthCamera::OnNewDepthFrame | ( | const float * | _image, |
unsigned int | _width, | ||
unsigned int | _height, | ||
unsigned int | _depth, | ||
const std::string & | _format | ||
) | [protected, virtual] |
Update the controller.
Definition at line 187 of file gazebo_ros_depth_camera.cpp.
void gazebo::GazeboRosDepthCamera::OnNewImageFrame | ( | const unsigned char * | _image, |
unsigned int | _width, | ||
unsigned int | _height, | ||
unsigned int | _depth, | ||
const std::string & | _format | ||
) | [protected, virtual] |
Update the controller.
Definition at line 287 of file gazebo_ros_depth_camera.cpp.
void gazebo::GazeboRosDepthCamera::OnNewRGBPointCloud | ( | const float * | _pcd, |
unsigned int | _width, | ||
unsigned int | _height, | ||
unsigned int | _depth, | ||
const std::string & | _format | ||
) | [protected, virtual] |
Update the controller.
Definition at line 223 of file gazebo_ros_depth_camera.cpp.
void gazebo::GazeboRosDepthCamera::PointCloudConnect | ( | ) | [private] |
Definition at line 142 of file gazebo_ros_depth_camera.cpp.
void gazebo::GazeboRosDepthCamera::PointCloudDisconnect | ( | ) | [private] |
Definition at line 150 of file gazebo_ros_depth_camera.cpp.
void gazebo::GazeboRosDepthCamera::PublishCameraInfo | ( | ) | [protected, virtual] |
Reimplemented from gazebo::GazeboRosCameraUtils.
Definition at line 480 of file gazebo_ros_depth_camera.cpp.
Definition at line 146 of file gazebo_ros_depth_camera.h.
std::string gazebo::GazeboRosDepthCamera::depth_image_camera_info_topic_name_ [private] |
Definition at line 139 of file gazebo_ros_depth_camera.h.
int gazebo::GazeboRosDepthCamera::depth_image_connect_count_ [private] |
Keep track of number of connctions for point clouds.
Definition at line 105 of file gazebo_ros_depth_camera.h.
sensor_msgs::Image gazebo::GazeboRosDepthCamera::depth_image_msg_ [private] |
Definition at line 124 of file gazebo_ros_depth_camera.h.
Definition at line 120 of file gazebo_ros_depth_camera.h.
std::string gazebo::GazeboRosDepthCamera::depth_image_topic_name_ [private] |
image where each pixel contains the depth information
Definition at line 138 of file gazebo_ros_depth_camera.h.
int gazebo::GazeboRosDepthCamera::depth_info_connect_count_ [private] |
Definition at line 140 of file gazebo_ros_depth_camera.h.
common::Time gazebo::GazeboRosDepthCamera::depth_sensor_update_time_ [private] |
Definition at line 145 of file gazebo_ros_depth_camera.h.
common::Time gazebo::GazeboRosDepthCamera::last_depth_image_camera_info_update_time_ [private] |
Definition at line 108 of file gazebo_ros_depth_camera.h.
Definition at line 148 of file gazebo_ros_depth_camera.h.
int gazebo::GazeboRosDepthCamera::point_cloud_connect_count_ [private] |
Keep track of number of connctions for point clouds.
Definition at line 100 of file gazebo_ros_depth_camera.h.
double gazebo::GazeboRosDepthCamera::point_cloud_cutoff_ [private] |
Definition at line 126 of file gazebo_ros_depth_camera.h.
sensor_msgs::PointCloud2 gazebo::GazeboRosDepthCamera::point_cloud_msg_ [private] |
PCL point cloud message.
Definition at line 123 of file gazebo_ros_depth_camera.h.
A pointer to the ROS node. A node will be instantiated if it does not exist.
Definition at line 119 of file gazebo_ros_depth_camera.h.
std::string gazebo::GazeboRosDepthCamera::point_cloud_topic_name_ [private] |
ROS image topic name.
Definition at line 129 of file gazebo_ros_depth_camera.h.