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

GazeboRosProsilica Controller. More...

#include <gazebo_ros_prosilica.h>

List of all members.

Public Member Functions

 GazeboRosProsilica (Entity *parent)
 Constructor.
virtual ~GazeboRosProsilica ()
 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 pollCallback (polled_camera::GetPolledImage::Request &req, polled_camera::GetPolledImage::Response &rsp, sensor_msgs::Image &image, sensor_msgs::CameraInfo &info)
void ProsilicaQueueThread ()
void PublishCameraInfo ()
void PutCameraData ()

Static Private Member Functions

static void mouse_cb (int event, int x, int y, int flags, void *param)
 does nothing for now

Private Attributes

ros::Publisher camera_info_pub_
sensor_msgs::CameraInfo cameraInfoMsg
std::string cameraInfoTopicName
ParamT< std::string > * cameraInfoTopicNameP
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 message
std::string imageTopicName
 ROS image topic name.
ParamT< std::string > * imageTopicNameP
 Parameters.
int infoConnectCount
boost::mutex lock
 A mutex to lock access to fields that are used in ROS message callbacks.
std::string mode_
MonoCameraSensor * myParent
 A pointer to the parent camera sensor.
polled_camera::PublicationServer poll_srv_
 image_transport
std::string pollServiceName
ParamT< std::string > * pollServiceNameP
boost::thread prosilica_callback_queue_thread_
ros::CallbackQueue prosilica_queue_
std::string robotNamespace
ParamT< std::string > * robotNamespaceP
 for setting ROS name space
sensor_msgs::CameraInfo * roiCameraInfoMsg
sensor_msgs::Image * roiImageMsg
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

GazeboRosProsilica Controller.

Definition at line 134 of file gazebo_ros_prosilica.h.


Constructor & Destructor Documentation

gazebo::GazeboRosProsilica::GazeboRosProsilica ( Entity *  parent  ) 

Constructor.

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

Definition at line 65 of file gazebo_ros_prosilica.cpp.

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

Destructor.

Definition at line 98 of file gazebo_ros_prosilica.cpp.


Member Function Documentation

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

Finalize the controller, unadvertise topics.

Definition at line 911 of file gazebo_ros_prosilica.cpp.

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

Definition at line 286 of file gazebo_ros_prosilica.cpp.

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

Definition at line 292 of file gazebo_ros_prosilica.cpp.

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

Definition at line 302 of file gazebo_ros_prosilica.cpp.

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

Definition at line 308 of file gazebo_ros_prosilica.cpp.

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

Init the controller.

Compute camera parameters if set to 0

Definition at line 212 of file gazebo_ros_prosilica.cpp.

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

Load the controller.

Parameters:
node XML config node

@todo: hardcoded per prosilica_camera wiki api, make this an urdf parameter

advertise topics for image and camera info

Definition at line 121 of file gazebo_ros_prosilica.cpp.

static void gazebo::GazeboRosProsilica::mouse_cb ( int  event,
int  x,
int  y,
int  flags,
void *  param 
) [inline, static, private]

does nothing for now

Definition at line 157 of file gazebo_ros_prosilica.h.

void gazebo::GazeboRosProsilica::pollCallback ( polled_camera::GetPolledImage::Request &  req,
polled_camera::GetPolledImage::Response &  rsp,
sensor_msgs::Image &  image,
sensor_msgs::CameraInfo &  info 
) [private]

Todo:
Support binning (maybe just cv::resize)
Todo:
Don't adjust K, P for ROI, set CameraInfo.roi fields instead
Todo:
D parameter order is k1, k2, t1, t2, k3
Todo:
: don't bother if there are no subscribers
Todo:
: publish to ros, thumbnails and rect image in the Update call?

Definition at line 565 of file gazebo_ros_prosilica.cpp.

void gazebo::GazeboRosProsilica::ProsilicaQueueThread (  )  [private]
void gazebo::GazeboRosProsilica::PublishCameraInfo (  )  [private]

Definition at line 505 of file gazebo_ros_prosilica.cpp.

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

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

Definition at line 346 of file gazebo_ros_prosilica.cpp.

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

Update the controller.

Todo:
: consider adding thumbnailing feature here if subscribed.

publish CameraInfo if in continuous mode, otherwise triggered by poll

Definition at line 318 of file gazebo_ros_prosilica.cpp.


Member Data Documentation

Definition at line 182 of file gazebo_ros_prosilica.h.

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

Definition at line 200 of file gazebo_ros_prosilica.h.

Definition at line 227 of file gazebo_ros_prosilica.h.

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

Definition at line 206 of file gazebo_ros_prosilica.h.

Definition at line 230 of file gazebo_ros_prosilica.h.

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

Definition at line 211 of file gazebo_ros_prosilica.h.

Definition at line 229 of file gazebo_ros_prosilica.h.

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

Definition at line 210 of file gazebo_ros_prosilica.h.

Definition at line 231 of file gazebo_ros_prosilica.h.

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

Definition at line 212 of file gazebo_ros_prosilica.h.

Definition at line 248 of file gazebo_ros_prosilica.h.

Definition at line 234 of file gazebo_ros_prosilica.h.

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

Definition at line 215 of file gazebo_ros_prosilica.h.

Definition at line 235 of file gazebo_ros_prosilica.h.

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

Definition at line 216 of file gazebo_ros_prosilica.h.

Definition at line 236 of file gazebo_ros_prosilica.h.

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

Definition at line 217 of file gazebo_ros_prosilica.h.

Definition at line 237 of file gazebo_ros_prosilica.h.

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

Definition at line 218 of file gazebo_ros_prosilica.h.

Definition at line 238 of file gazebo_ros_prosilica.h.

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

Definition at line 219 of file gazebo_ros_prosilica.h.

Definition at line 232 of file gazebo_ros_prosilica.h.

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

Definition at line 213 of file gazebo_ros_prosilica.h.

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 242 of file gazebo_ros_prosilica.h.

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

Definition at line 208 of file gazebo_ros_prosilica.h.

Definition at line 233 of file gazebo_ros_prosilica.h.

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

Definition at line 214 of file gazebo_ros_prosilica.h.

size of image buffer

Definition at line 248 of file gazebo_ros_prosilica.h.

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

Definition at line 181 of file gazebo_ros_prosilica.h.

Keep track of number of connctions.

Definition at line 157 of file gazebo_ros_prosilica.h.

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

ros message

construct raw stereo message

Definition at line 198 of file gazebo_ros_prosilica.h.

ROS image topic name.

Definition at line 226 of file gazebo_ros_prosilica.h.

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

Parameters.

Definition at line 205 of file gazebo_ros_prosilica.h.

Definition at line 163 of file gazebo_ros_prosilica.h.

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

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

Definition at line 245 of file gazebo_ros_prosilica.h.

std::string gazebo::GazeboRosProsilica::mode_ [private]

Definition at line 179 of file gazebo_ros_prosilica.h.

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

A pointer to the parent camera sensor.

Definition at line 171 of file gazebo_ros_prosilica.h.

polled_camera::PublicationServer gazebo::GazeboRosProsilica::poll_srv_ [private]

image_transport

Definition at line 177 of file gazebo_ros_prosilica.h.

Definition at line 228 of file gazebo_ros_prosilica.h.

ParamT<std::string>* gazebo::GazeboRosProsilica::pollServiceNameP [private]

Definition at line 207 of file gazebo_ros_prosilica.h.

Definition at line 255 of file gazebo_ros_prosilica.h.

ros::CallbackQueue gazebo::GazeboRosProsilica::prosilica_queue_ [private]

Definition at line 253 of file gazebo_ros_prosilica.h.

Definition at line 223 of file gazebo_ros_prosilica.h.

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

for setting ROS name space

Definition at line 222 of file gazebo_ros_prosilica.h.

sensor_msgs::CameraInfo* gazebo::GazeboRosProsilica::roiCameraInfoMsg [private]

Definition at line 201 of file gazebo_ros_prosilica.h.

sensor_msgs::Image* gazebo::GazeboRosProsilica::roiImageMsg [private]

Definition at line 199 of file gazebo_ros_prosilica.h.

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

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

Definition at line 174 of file gazebo_ros_prosilica.h.

Definition at line 250 of file gazebo_ros_prosilica.h.

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

Definition at line 249 of file gazebo_ros_prosilica.h.

Definition at line 248 of file gazebo_ros_prosilica.h.


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


pr2_gazebo_plugins
Author(s): Sachin Chitta, Stu Glaser, John Hsu
autogenerated on Fri Jan 11 09:32:25 2013