Public Member Functions | Protected Member Functions | Private Member Functions | Static Private Member Functions | Private Attributes
gazebo::GazeboRosProsilica Class Reference

#include <gazebo_ros_prosilica.h>

Inheritance diagram for gazebo::GazeboRosProsilica:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 GazeboRosProsilica ()
 Constructor.
void Load (sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
 Load the controller.
virtual ~GazeboRosProsilica ()
 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 does nothing for depth.
virtual void OnNewImageFrame (const unsigned char *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format)
 Update the controller.

Private Member Functions

void pollCallback (polled_camera::GetPolledImage::Request &req, polled_camera::GetPolledImage::Response &rsp, sensor_msgs::Image &image, sensor_msgs::CameraInfo &info)

Static Private Member Functions

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

Private Attributes

std::string mode_
std::string mode_param_name
polled_camera::PublicationServer poll_srv_
 image_transport
std::string pollServiceName
 ROS image topic name.
sensor_msgs::CameraInfo * roiCameraInfoMsg
sensor_msgs::Image * roiImageMsg
 ros message

Detailed Description

Definition at line 51 of file gazebo_ros_prosilica.h.


Constructor & Destructor Documentation

Constructor.

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

Definition at line 70 of file gazebo_ros_prosilica.cpp.

Destructor.

Definition at line 76 of file gazebo_ros_prosilica.cpp.


Member Function Documentation

void gazebo::GazeboRosProsilica::Load ( sensors::SensorPtr  _parent,
sdf::ElementPtr  _sdf 
)

Load the controller.

Parameters:
nodeXML config node

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

Reimplemented from gazebo::GazeboRosCameraUtils.

Definition at line 84 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 65 of file gazebo_ros_prosilica.h.

virtual void gazebo::GazeboRosProsilica::OnNewDepthFrame ( const float *  _image,
unsigned int  _width,
unsigned int  _height,
unsigned int  _depth,
const std::string &  _format 
) [inline, protected, virtual]

Update the controller does nothing for depth.

Definition at line 100 of file gazebo_ros_prosilica.h.

void gazebo::GazeboRosProsilica::OnNewImageFrame ( const unsigned char *  _image,
unsigned int  _width,
unsigned int  _height,
unsigned int  _depth,
const std::string &  _format 
) [protected, virtual]

Update the controller.

Todo:
: consider adding thumbnailing feature here if subscribed.

publish CameraInfo

Definition at line 126 of file gazebo_ros_prosilica.cpp.

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 178 of file gazebo_ros_prosilica.cpp.


Member Data Documentation

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

Definition at line 70 of file gazebo_ros_prosilica.h.

Definition at line 72 of file gazebo_ros_prosilica.h.

image_transport

Definition at line 65 of file gazebo_ros_prosilica.h.

ROS image topic name.

Definition at line 91 of file gazebo_ros_prosilica.h.

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

Definition at line 88 of file gazebo_ros_prosilica.h.

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

ros message

construct raw stereo message

Definition at line 87 of file gazebo_ros_prosilica.h.


The documentation for this class was generated from the following files:


pr2_gazebo_plugins
Author(s): Sachin Chitta, Stu Glaser, John Hsu
autogenerated on Thu Jan 2 2014 11:45:00