#include <gazebo_ros_depth_camera.h>
|
virtual void | OnNewDepthFrame (const float *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format) |
| Update the controller. More...
|
|
virtual void | OnNewImageFrame (const unsigned char *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format) |
| Update the controller. More...
|
|
virtual void | OnNewRGBPointCloud (const float *_pcd, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format) |
| Update the controller. More...
|
|
virtual void | PublishCameraInfo () |
|
|
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 | PointCloudConnect () |
|
void | PointCloudDisconnect () |
|
| GazeboRosCameraUtils () |
| Constructor. More...
|
|
void | Load (sensors::SensorPtr _parent, sdf::ElementPtr _sdf, const std::string &_camera_name_suffix="") |
| Load the plugin. More...
|
|
void | Load (sensors::SensorPtr _parent, sdf::ElementPtr _sdf, const std::string &_camera_name_suffix, double _hack_baseline) |
| 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 (ros::Publisher camera_info_publisher) |
| Publish CameraInfo to the ROS topic. More...
|
|
void | PublishCameraInfo (common::Time &last_update_time) |
|
void | PublishCameraInfo () |
|
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 () |
|
Definition at line 60 of file gazebo_ros_depth_camera.h.
gazebo::GazeboRosDepthCamera::GazeboRosDepthCamera |
( |
| ) |
|
gazebo::GazeboRosDepthCamera::~GazeboRosDepthCamera |
( |
| ) |
|
void gazebo::GazeboRosDepthCamera::Advertise |
( |
| ) |
|
|
virtual |
void gazebo::GazeboRosDepthCamera::DepthImageConnect |
( |
| ) |
|
|
private |
void gazebo::GazeboRosDepthCamera::DepthImageDisconnect |
( |
| ) |
|
|
private |
void gazebo::GazeboRosDepthCamera::DepthInfoConnect |
( |
| ) |
|
|
private |
void gazebo::GazeboRosDepthCamera::DepthInfoDisconnect |
( |
| ) |
|
|
private |
void gazebo::GazeboRosDepthCamera::FillDepthImage |
( |
const float * |
_src | ) |
|
|
private |
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 |
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 |
void gazebo::GazeboRosDepthCamera::FillPointdCloud |
( |
const float * |
_src | ) |
|
|
private |
void gazebo::GazeboRosDepthCamera::InfoConnect |
( |
| ) |
|
|
private |
void gazebo::GazeboRosDepthCamera::InfoDisconnect |
( |
| ) |
|
|
private |
void gazebo::GazeboRosDepthCamera::Load |
( |
sensors::SensorPtr |
_parent, |
|
|
sdf::ElementPtr |
_sdf |
|
) |
| |
|
virtual |
void gazebo::GazeboRosDepthCamera::OnNewDepthFrame |
( |
const float * |
_image, |
|
|
unsigned int |
_width, |
|
|
unsigned int |
_height, |
|
|
unsigned int |
_depth, |
|
|
const std::string & |
_format |
|
) |
| |
|
protectedvirtual |
void gazebo::GazeboRosDepthCamera::OnNewImageFrame |
( |
const unsigned char * |
_image, |
|
|
unsigned int |
_width, |
|
|
unsigned int |
_height, |
|
|
unsigned int |
_depth, |
|
|
const std::string & |
_format |
|
) |
| |
|
protectedvirtual |
void gazebo::GazeboRosDepthCamera::OnNewRGBPointCloud |
( |
const float * |
_pcd, |
|
|
unsigned int |
_width, |
|
|
unsigned int |
_height, |
|
|
unsigned int |
_depth, |
|
|
const std::string & |
_format |
|
) |
| |
|
protectedvirtual |
void gazebo::GazeboRosDepthCamera::PointCloudConnect |
( |
| ) |
|
|
private |
void gazebo::GazeboRosDepthCamera::PointCloudDisconnect |
( |
| ) |
|
|
private |
void gazebo::GazeboRosDepthCamera::PublishCameraInfo |
( |
| ) |
|
|
protectedvirtual |
ros::Publisher gazebo::GazeboRosDepthCamera::depth_image_camera_info_pub_ |
|
protected |
std::string gazebo::GazeboRosDepthCamera::depth_image_camera_info_topic_name_ |
|
private |
int gazebo::GazeboRosDepthCamera::depth_image_connect_count_ |
|
private |
sensor_msgs::Image gazebo::GazeboRosDepthCamera::depth_image_msg_ |
|
private |
std::string gazebo::GazeboRosDepthCamera::depth_image_topic_name_ |
|
private |
int gazebo::GazeboRosDepthCamera::depth_info_connect_count_ |
|
private |
common::Time gazebo::GazeboRosDepthCamera::depth_sensor_update_time_ |
|
private |
common::Time gazebo::GazeboRosDepthCamera::last_depth_image_camera_info_update_time_ |
|
private |
int gazebo::GazeboRosDepthCamera::point_cloud_connect_count_ |
|
private |
double gazebo::GazeboRosDepthCamera::point_cloud_cutoff_ |
|
private |
sensor_msgs::PointCloud2 gazebo::GazeboRosDepthCamera::point_cloud_msg_ |
|
private |
std::string gazebo::GazeboRosDepthCamera::point_cloud_topic_name_ |
|
private |
The documentation for this class was generated from the following files: