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.

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 ImageConnect ()
void ImageDisconnect ()
void InfoConnect ()
void InfoDisconnect ()
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
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
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
ros::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.
boost::mutex lock
 A mutex to lock access to fields that are used in ROS message callbacks.
MonoCameraSensor * myParent
 A pointer to the parent camera sensor.
std::string robotNamespace
ParamT< std::string > * robotNamespaceP
 for setting ROS name space
ros::NodeHandle * rosnode_
 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 98 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 57 of file gazebo_ros_camera.cpp.

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

Destructor.

Definition at line 92 of file gazebo_ros_camera.cpp.


Member Function Documentation

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

Finalize the controller, unadvertise topics.

Definition at line 328 of file gazebo_ros_camera.cpp.

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

Definition at line 217 of file gazebo_ros_camera.cpp.

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

Definition at line 223 of file gazebo_ros_camera.cpp.

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

Definition at line 190 of file gazebo_ros_camera.cpp.

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

Definition at line 196 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 233 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 113 of file gazebo_ros_camera.cpp.

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

Publish CameraInfo to the ROS topic.

Definition at line 504 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

Definition at line 342 of file gazebo_ros_camera.cpp.

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

Definition at line 203 of file gazebo_ros_camera.cpp.

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

Definition at line 210 of file gazebo_ros_camera.cpp.

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

Update the controller.

publish CameraInfo

Definition at line 305 of file gazebo_ros_camera.cpp.


Member Data Documentation

Definition at line 142 of file gazebo_ros_camera.h.

Definition at line 195 of file gazebo_ros_camera.h.

sensor_msgs::CameraInfo gazebo::GazeboRosCamera::cameraInfoMsg [private]

Definition at line 146 of file gazebo_ros_camera.h.

ROS camera_info topic name.

Definition at line 171 of file gazebo_ros_camera.h.

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

Definition at line 150 of file gazebo_ros_camera.h.

Definition at line 196 of file gazebo_ros_camera.h.

double gazebo::GazeboRosCamera::Cx [private]

Definition at line 177 of file gazebo_ros_camera.h.

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

Definition at line 154 of file gazebo_ros_camera.h.

Definition at line 176 of file gazebo_ros_camera.h.

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

Definition at line 153 of file gazebo_ros_camera.h.

double gazebo::GazeboRosCamera::Cy [private]

Definition at line 178 of file gazebo_ros_camera.h.

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

Definition at line 155 of file gazebo_ros_camera.h.

Definition at line 191 of file gazebo_ros_camera.h.

Definition at line 181 of file gazebo_ros_camera.h.

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

Definition at line 158 of file gazebo_ros_camera.h.

Definition at line 182 of file gazebo_ros_camera.h.

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

Definition at line 159 of file gazebo_ros_camera.h.

Definition at line 183 of file gazebo_ros_camera.h.

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

Definition at line 160 of file gazebo_ros_camera.h.

Definition at line 184 of file gazebo_ros_camera.h.

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

Definition at line 161 of file gazebo_ros_camera.h.

Definition at line 185 of file gazebo_ros_camera.h.

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

Definition at line 162 of file gazebo_ros_camera.h.

Definition at line 179 of file gazebo_ros_camera.h.

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

Definition at line 156 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 174 of file gazebo_ros_camera.h.

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

Definition at line 151 of file gazebo_ros_camera.h.

Definition at line 180 of file gazebo_ros_camera.h.

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

Definition at line 157 of file gazebo_ros_camera.h.

size of image buffer

Definition at line 191 of file gazebo_ros_camera.h.

ros::Publisher gazebo::GazeboRosCamera::image_pub_ [private]

Definition at line 142 of file gazebo_ros_camera.h.

Keep track of number of connctions.

Definition at line 126 of file gazebo_ros_camera.h.

sensor_msgs::Image gazebo::GazeboRosCamera::imageMsg [private]

ROS image message.

Definition at line 145 of file gazebo_ros_camera.h.

ROS image topic name.

Definition at line 169 of file gazebo_ros_camera.h.

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

Parameters.

Definition at line 149 of file gazebo_ros_camera.h.

Keep track of number of connctions for CameraInfo.

Definition at line 131 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 188 of file gazebo_ros_camera.h.

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

A pointer to the parent camera sensor.

Definition at line 138 of file gazebo_ros_camera.h.

Definition at line 166 of file gazebo_ros_camera.h.

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

for setting ROS name space

Definition at line 165 of file gazebo_ros_camera.h.

ros::NodeHandle* gazebo::GazeboRosCamera::rosnode_ [private]

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

Definition at line 141 of file gazebo_ros_camera.h.

Definition at line 193 of file gazebo_ros_camera.h.

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

Definition at line 192 of file gazebo_ros_camera.h.

Definition at line 191 of file gazebo_ros_camera.h.


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


gazebo_plugins
Author(s): Sachin Chitta, Stu Glaser, John Hsu
autogenerated on Fri Jan 11 10:09:35 2013