$search

gazebo::GazeboRosCamera Class Reference
[Ros Camera Plugin XML Reference and Example]

GazeboRosCamera Controller. More...

#include <gazebo_ros_camera.h>

List of all members.

Public Member Functions

 GazeboRosCamera (Entity *parent)
 Constructor.
virtual ~GazeboRosCamera ()
 Destructor.

Public Attributes

 EIGEN_MAKE_ALIGNED_OPERATOR_NEW

Protected Member Functions

virtual void FiniChild ()
 Finalize the controller, unadvertise topics.
virtual void InitChild ()
 Init the controller.
virtual void LoadChild (XMLConfigNode *node)
 Load the controller.
virtual void UpdateChild ()
 Update the controller.

Private Member Functions

void configCallback (gazebo_plugins::GazeboRosCameraConfig &config, uint32_t level)
void convertImageFormat (unsigned char *dst, const unsigned char *src)
bool fillDepthImage (pcl::PointCloud< pcl::PointXYZ > &point_cloud, uint32_t rows_arg, uint32_t cols_arg, uint32_t step_arg, void *data_arg)
void ImageConnect ()
void ImageDisconnect ()
void InfoConnect ()
void InfoDisconnect ()
void PointCloudConnect ()
void PointCloudDisconnect ()
void PublishCameraInfo ()
 Publish CameraInfo to the ROS topic.
void PutCameraData ()
 Put camera data to the ROS topic.
void SetHFOV (const std_msgs::Float64::ConstPtr &hfov)
void SetUpdateRate (const std_msgs::Float64::ConstPtr &update_rate)

Private Attributes

ros::Publisher camera_info_pub_
ros::Subscriber cameraHFOVSubscriber_
sensor_msgs::CameraInfo cameraInfoMsg
std::string cameraInfoTopicName
 ROS camera_info topic name.
ParamT< std::string > * cameraInfoTopicNameP
std::string cameraName
 ROS camera name.
ParamT< std::string > * cameraNameP
ros::Subscriber cameraUpdateRateSubscriber_
double Cx
ParamT< double > * CxP
double CxPrime
ParamT< double > * CxPrimeP
double Cy
ParamT< double > * CyP
int depth
double distortion_k1
ParamT< double > * distortion_k1P
double distortion_k2
ParamT< double > * distortion_k2P
double distortion_k3
ParamT< double > * distortion_k3P
double distortion_t1
ParamT< double > * distortion_t1P
double distortion_t2
ParamT< double > * distortion_t2P
dynamic_reconfigure::Server
< gazebo_plugins::GazeboRosCameraConfig > * 
dyn_srv_
std::string dynamicReconfigureName
double focal_length
ParamT< double > * focal_lengthP
std::string frameName
 ROS frame transform name to use in the image message header. This should typically match the link name the sensor is attached.
ParamT< std::string > * frameNameP
double hack_baseline
ParamT< double > * hack_baselineP
int height
 size of image buffer
image_transport::Publisher image_pub_
int imageConnectCount
 Keep track of number of connctions.
sensor_msgs::Image imageMsg
 ROS image message.
std::string imageTopicName
 ROS image topic name.
ParamT< std::string > * imageTopicNameP
 Parameters.
int infoConnectCount
 Keep track of number of connctions for CameraInfo.
image_transport::ImageTransportitnode_
Time last_camera_info_pub_time_
Time last_image_pub_time_
Time last_point_cloud_pub_time_
boost::mutex lock
 A mutex to lock access to fields that are used in ROS message callbacks.
nodelet::Loadermanager_
ros::NodeHandlemanagernode_
MonoCameraSensor * myParent
 A pointer to the parent camera sensor.
ros::Publisher point_cloud_pub_
int pointCloudConnectCount
 Keep track of number of connctions for point clouds.
double pointCloudCutoff
ParamT< double > * pointCloudCutoffP
pcl::PointCloud< pcl::PointXYZ > pointCloudMsg
std::string pointCloudTopicName
 ROS point cloud topic name.
ParamT< std::string > * pointCloudTopicNameP
std::string robotNamespace
ParamT< std::string > * robotNamespaceP
 for setting ROS name space
ros::NodeHandlerosnode_
 A pointer to the ROS node. A node will be instantiated if it does not exist.
int skip
std::string type
int width

Detailed Description

GazeboRosCamera Controller.

Definition at line 112 of file gazebo_ros_camera.h.


Constructor & Destructor Documentation

gazebo::GazeboRosCamera::GazeboRosCamera ( Entity *  parent  ) 

Constructor.

Parameters:
parent The parent entity, must be a Model or a Sensor

Definition at line 65 of file gazebo_ros_camera.cpp.

gazebo::GazeboRosCamera::~GazeboRosCamera (  )  [virtual]

Destructor.

Definition at line 115 of file gazebo_ros_camera.cpp.


Member Function Documentation

void gazebo::GazeboRosCamera::configCallback ( gazebo_plugins::GazeboRosCameraConfig &  config,
uint32_t  level 
) [private]

Definition at line 106 of file gazebo_ros_camera.cpp.

void gazebo::GazeboRosCamera::convertImageFormat ( unsigned char *  dst,
const unsigned char *  src 
) [private]

Definition at line 542 of file gazebo_ros_camera.cpp.

bool gazebo::GazeboRosCamera::fillDepthImage ( pcl::PointCloud< pcl::PointXYZ > &  point_cloud,
uint32_t  rows_arg,
uint32_t  cols_arg,
uint32_t  step_arg,
void *  data_arg 
) [private]

Definition at line 650 of file gazebo_ros_camera.cpp.

void gazebo::GazeboRosCamera::FiniChild (  )  [protected, virtual]

Finalize the controller, unadvertise topics.

Definition at line 423 of file gazebo_ros_camera.cpp.

void gazebo::GazeboRosCamera::ImageConnect (  )  [private]

Definition at line 275 of file gazebo_ros_camera.cpp.

void gazebo::GazeboRosCamera::ImageDisconnect (  )  [private]

Definition at line 282 of file gazebo_ros_camera.cpp.

void gazebo::GazeboRosCamera::InfoConnect (  )  [private]

Definition at line 248 of file gazebo_ros_camera.cpp.

void gazebo::GazeboRosCamera::InfoDisconnect (  )  [private]

Definition at line 254 of file gazebo_ros_camera.cpp.

void gazebo::GazeboRosCamera::InitChild (  )  [protected, virtual]

Init the controller.

Compute camera parameters if set to 0

Definition at line 318 of file gazebo_ros_camera.cpp.

void gazebo::GazeboRosCamera::LoadChild ( XMLConfigNode *  node  )  [protected, virtual]

Load the controller.

Parameters:
node XML config node

Definition at line 140 of file gazebo_ros_camera.cpp.

void gazebo::GazeboRosCamera::PointCloudConnect (  )  [private]

Definition at line 296 of file gazebo_ros_camera.cpp.

void gazebo::GazeboRosCamera::PointCloudDisconnect (  )  [private]

Definition at line 304 of file gazebo_ros_camera.cpp.

void gazebo::GazeboRosCamera::PublishCameraInfo (  )  [private]

Publish CameraInfo to the ROS topic.

Definition at line 711 of file gazebo_ros_camera.cpp.

void gazebo::GazeboRosCamera::PutCameraData (  )  [private]

Put camera data to the ROS topic.

Todo:
: don't bother if there are no subscribers

copy from depth to pointCloudMsg

Definition at line 439 of file gazebo_ros_camera.cpp.

void gazebo::GazeboRosCamera::SetHFOV ( const std_msgs::Float64::ConstPtr &  hfov  )  [private]

Definition at line 261 of file gazebo_ros_camera.cpp.

void gazebo::GazeboRosCamera::SetUpdateRate ( const std_msgs::Float64::ConstPtr &  update_rate  )  [private]

Definition at line 268 of file gazebo_ros_camera.cpp.

void gazebo::GazeboRosCamera::UpdateChild (  )  [protected, virtual]

Update the controller.

publish CameraInfo

Definition at line 403 of file gazebo_ros_camera.cpp.


Member Data Documentation

Definition at line 170 of file gazebo_ros_camera.h.

Definition at line 234 of file gazebo_ros_camera.h.

Definition at line 176 of file gazebo_ros_camera.h.

ROS camera_info topic name.

Definition at line 207 of file gazebo_ros_camera.h.

ParamT<std::string>* gazebo::GazeboRosCamera::cameraInfoTopicNameP [private]

Definition at line 181 of file gazebo_ros_camera.h.

std::string gazebo::GazeboRosCamera::cameraName [private]

ROS camera name.

Definition at line 203 of file gazebo_ros_camera.h.

ParamT<std::string>* gazebo::GazeboRosCamera::cameraNameP [private]

Definition at line 183 of file gazebo_ros_camera.h.

Definition at line 235 of file gazebo_ros_camera.h.

double gazebo::GazeboRosCamera::Cx [private]

Definition at line 215 of file gazebo_ros_camera.h.

ParamT<double>* gazebo::GazeboRosCamera::CxP [private]

Definition at line 187 of file gazebo_ros_camera.h.

Definition at line 214 of file gazebo_ros_camera.h.

ParamT<double>* gazebo::GazeboRosCamera::CxPrimeP [private]

Definition at line 186 of file gazebo_ros_camera.h.

double gazebo::GazeboRosCamera::Cy [private]

Definition at line 216 of file gazebo_ros_camera.h.

ParamT<double>* gazebo::GazeboRosCamera::CyP [private]

Definition at line 188 of file gazebo_ros_camera.h.

Definition at line 230 of file gazebo_ros_camera.h.

Definition at line 220 of file gazebo_ros_camera.h.

ParamT<double>* gazebo::GazeboRosCamera::distortion_k1P [private]

Definition at line 192 of file gazebo_ros_camera.h.

Definition at line 221 of file gazebo_ros_camera.h.

ParamT<double>* gazebo::GazeboRosCamera::distortion_k2P [private]

Definition at line 193 of file gazebo_ros_camera.h.

Definition at line 222 of file gazebo_ros_camera.h.

ParamT<double>* gazebo::GazeboRosCamera::distortion_k3P [private]

Definition at line 194 of file gazebo_ros_camera.h.

Definition at line 223 of file gazebo_ros_camera.h.

ParamT<double>* gazebo::GazeboRosCamera::distortion_t1P [private]

Definition at line 195 of file gazebo_ros_camera.h.

Definition at line 224 of file gazebo_ros_camera.h.

ParamT<double>* gazebo::GazeboRosCamera::distortion_t2P [private]

Definition at line 196 of file gazebo_ros_camera.h.

dynamic_reconfigure::Server<gazebo_plugins::GazeboRosCameraConfig>* gazebo::GazeboRosCamera::dyn_srv_ [private]

Definition at line 241 of file gazebo_ros_camera.h.

Definition at line 246 of file gazebo_ros_camera.h.

Definition at line 254 of file gazebo_ros_camera.h.

Definition at line 217 of file gazebo_ros_camera.h.

ParamT<double>* gazebo::GazeboRosCamera::focal_lengthP [private]

Definition at line 189 of file gazebo_ros_camera.h.

std::string gazebo::GazeboRosCamera::frameName [private]

ROS frame transform name to use in the image message header. This should typically match the link name the sensor is attached.

Definition at line 212 of file gazebo_ros_camera.h.

ParamT<std::string>* gazebo::GazeboRosCamera::frameNameP [private]

Definition at line 184 of file gazebo_ros_camera.h.

Definition at line 218 of file gazebo_ros_camera.h.

ParamT<double>* gazebo::GazeboRosCamera::hack_baselineP [private]

Definition at line 190 of file gazebo_ros_camera.h.

size of image buffer

Definition at line 230 of file gazebo_ros_camera.h.

Definition at line 171 of file gazebo_ros_camera.h.

Keep track of number of connctions.

Definition at line 140 of file gazebo_ros_camera.h.

ROS image message.

Definition at line 175 of file gazebo_ros_camera.h.

ROS image topic name.

Definition at line 205 of file gazebo_ros_camera.h.

ParamT<std::string>* gazebo::GazeboRosCamera::imageTopicNameP [private]

Parameters.

Definition at line 180 of file gazebo_ros_camera.h.

Keep track of number of connctions for CameraInfo.

Definition at line 150 of file gazebo_ros_camera.h.

Definition at line 172 of file gazebo_ros_camera.h.

Definition at line 238 of file gazebo_ros_camera.h.

Definition at line 238 of file gazebo_ros_camera.h.

Definition at line 238 of file gazebo_ros_camera.h.

boost::mutex gazebo::GazeboRosCamera::lock [private]

A mutex to lock access to fields that are used in ROS message callbacks.

Definition at line 227 of file gazebo_ros_camera.h.

Definition at line 169 of file gazebo_ros_camera.h.

Definition at line 168 of file gazebo_ros_camera.h.

MonoCameraSensor* gazebo::GazeboRosCamera::myParent [private]

A pointer to the parent camera sensor.

Definition at line 164 of file gazebo_ros_camera.h.

Definition at line 170 of file gazebo_ros_camera.h.

Keep track of number of connctions for point clouds.

Definition at line 145 of file gazebo_ros_camera.h.

Definition at line 219 of file gazebo_ros_camera.h.

ParamT<double>* gazebo::GazeboRosCamera::pointCloudCutoffP [private]

Definition at line 191 of file gazebo_ros_camera.h.

pcl::PointCloud<pcl::PointXYZ> gazebo::GazeboRosCamera::pointCloudMsg [private]

Definition at line 177 of file gazebo_ros_camera.h.

ROS point cloud topic name.

Definition at line 209 of file gazebo_ros_camera.h.

ParamT<std::string>* gazebo::GazeboRosCamera::pointCloudTopicNameP [private]

Definition at line 182 of file gazebo_ros_camera.h.

Definition at line 200 of file gazebo_ros_camera.h.

ParamT<std::string>* gazebo::GazeboRosCamera::robotNamespaceP [private]

for setting ROS name space

Definition at line 199 of file gazebo_ros_camera.h.

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

Definition at line 167 of file gazebo_ros_camera.h.

Definition at line 232 of file gazebo_ros_camera.h.

std::string gazebo::GazeboRosCamera::type [private]

Definition at line 231 of file gazebo_ros_camera.h.

Definition at line 230 of file gazebo_ros_camera.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


gazebo_plugins
Author(s): Sachin Chitta, Stu Glaser, John Hsu
autogenerated on Sat Mar 2 13:40:08 2013