#include <gazebo_ros_prosilica.h>

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 | |
Definition at line 51 of file gazebo_ros_prosilica.h.
Constructor.
| parent | The parent entity, must be a Model or a Sensor |
Definition at line 70 of file gazebo_ros_prosilica.cpp.
| gazebo::GazeboRosProsilica::~GazeboRosProsilica | ( | ) | [virtual] |
Destructor.
Definition at line 76 of file gazebo_ros_prosilica.cpp.
| void gazebo::GazeboRosProsilica::Load | ( | sensors::SensorPtr | _parent, |
| sdf::ElementPtr | _sdf | ||
| ) | [virtual] |
Load the controller.
| node | XML 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.
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] |
Definition at line 178 of file gazebo_ros_prosilica.cpp.
std::string gazebo::GazeboRosProsilica::mode_ [private] |
Definition at line 70 of file gazebo_ros_prosilica.h.
std::string gazebo::GazeboRosProsilica::mode_param_name [private] |
Definition at line 72 of file gazebo_ros_prosilica.h.
Definition at line 65 of file gazebo_ros_prosilica.h.
std::string gazebo::GazeboRosProsilica::pollServiceName [private] |
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] |