Public Member Functions | Protected Member Functions | Private Member Functions | Static Private Member Functions | Private Attributes | List of all members
gazebo::GazeboRosProsilica Class Reference

#include <gazebo_ros_prosilica.h>

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

Public Member Functions

 GazeboRosProsilica ()
 Constructor. More...
 
void Load (sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
 Load the controller. More...
 
virtual ~GazeboRosProsilica ()
 Destructor. More...
 

Protected Member Functions

virtual void OnNewImageFrame (const unsigned char *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format)
 Update the controller. More...
 

Private Member Functions

void Advertise ()
 
void pollCallback (polled_camera::GetPolledImage::Request &req, polled_camera::GetPolledImage::Response &rsp, sensor_msgs::Image &image, sensor_msgs::CameraInfo &info)
 
- Private Member Functions inherited from gazebo::GazeboRosCameraUtils
 GazeboRosCameraUtils ()
 Constructor. More...
 
void Load (sensors::SensorPtr _parent, sdf::ElementPtr _sdf, const std::string &_camera_name_suffix="")
 Load the plugin. More...
 
void Load (sensors::SensorPtr _parent, sdf::ElementPtr _sdf, const std::string &_camera_name_suffix, double _hack_baseline)
 Load the plugin. More...
 
event::ConnectionPtr OnLoad (const boost::function< void()> &)
 
 ~GazeboRosCameraUtils ()
 Destructor. More...
 
void CameraQueueThread ()
 
virtual bool CanTriggerCamera ()
 
void ImageConnect ()
 
void ImageDisconnect ()
 
void PublishCameraInfo (ros::Publisher camera_info_publisher)
 Publish CameraInfo to the ROS topic. More...
 
void PublishCameraInfo (common::Time &last_update_time)
 
void PublishCameraInfo ()
 
void PutCameraData (const unsigned char *_src)
 Put camera data to the ROS topic. More...
 
void PutCameraData (const unsigned char *_src, common::Time &last_update_time)
 
virtual void TriggerCamera ()
 

Static Private Member Functions

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

Private Attributes

event::ConnectionPtr load_connection_
 
std::string mode_
 
std::string mode_param_name
 
polled_camera::PublicationServer poll_srv_
 image_transport More...
 
std::string pollServiceName
 ROS image topic name. More...
 
sensor_msgs::CameraInfo * roiCameraInfoMsg
 
sensor_msgs::Image * roiImageMsg
 ros message More...
 
- Private Attributes inherited from gazebo::GazeboRosCameraUtils
bool border_crop_
 
boost::thread callback_queue_thread_
 
rendering::CameraPtr camera_
 
boost::shared_ptr< camera_info_manager::CameraInfoManagercamera_info_manager_
 
ros::Publisher camera_info_pub_
 camera info More...
 
std::string camera_info_topic_name_
 
ros::CallbackQueue camera_queue_
 
double cx_
 
double cx_prime_
 
double cy_
 
unsigned int depth_
 
double distortion_k1_
 
double distortion_k2_
 
double distortion_k3_
 
double distortion_t1_
 
double distortion_t2_
 
double focal_length_
 
std::string format_
 
std::string frame_name_
 ROS frame transform name to use in the image message header. This should typically match the link name the sensor is attached. More...
 
double hack_baseline_
 
unsigned int height_
 
boost::shared_ptr< int > image_connect_count_
 Keep track of number of image connections. More...
 
boost::shared_ptr< boost::mutex > image_connect_count_lock_
 A mutex to lock access to image_connect_count_. More...
 
sensor_msgs::Image image_msg_
 ROS image message. More...
 
image_transport::Publisher image_pub_
 
std::string image_topic_name_
 ROS image topic name. More...
 
bool initialized_
 True if camera util is initialized. More...
 
common::Time last_info_update_time_
 
common::Time last_update_time_
 
boost::mutex lock_
 A mutex to lock access to fields that are used in ROS message callbacks. More...
 
sensors::SensorPtr parentSensor_
 
ros::NodeHandlerosnode_
 A pointer to the ROS node. A node will be instantiated if it does not exist. More...
 
common::Time sensor_update_time_
 
int skip_
 
std::string trigger_topic_name_
 ROS trigger topic name. More...
 
std::string type_
 size of image buffer More...
 
double update_period_
 
double update_rate_
 update rate of this sensor More...
 
boost::shared_ptr< bool > was_active_
 Keep track when we activate this camera through ros subscription, was it already active? resume state when unsubscribed. More...
 
unsigned int width_
 
physics::WorldPtr world
 
physics::WorldPtr world_
 

Detailed Description

Definition at line 44 of file gazebo_ros_prosilica.h.

Constructor & Destructor Documentation

gazebo::GazeboRosProsilica::GazeboRosProsilica ( )

Constructor.

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

Definition at line 64 of file gazebo_ros_prosilica.cpp.

gazebo::GazeboRosProsilica::~GazeboRosProsilica ( )
virtual

Destructor.

Definition at line 70 of file gazebo_ros_prosilica.cpp.

Member Function Documentation

void gazebo::GazeboRosProsilica::Advertise ( )
private

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

Definition at line 93 of file gazebo_ros_prosilica.cpp.

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

Load the controller.

Parameters
nodeXML config node

Definition at line 78 of file gazebo_ros_prosilica.cpp.

static void gazebo::GazeboRosProsilica::mouse_cb ( int  event,
int  x,
int  y,
int  flags,
void *  param 
)
inlinestaticprivate

does nothing for now

Definition at line 58 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 
)
protectedvirtual

Update the controller.

Todo:
: consider adding thumbnailing feature here if subscribed.

Definition at line 125 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 167 of file gazebo_ros_prosilica.cpp.

Member Data Documentation

event::ConnectionPtr gazebo::GazeboRosProsilica::load_connection_
private

Definition at line 87 of file gazebo_ros_prosilica.h.

std::string gazebo::GazeboRosProsilica::mode_
private

Definition at line 63 of file gazebo_ros_prosilica.h.

std::string gazebo::GazeboRosProsilica::mode_param_name
private

Definition at line 65 of file gazebo_ros_prosilica.h.

polled_camera::PublicationServer gazebo::GazeboRosProsilica::poll_srv_
private

image_transport

Definition at line 58 of file gazebo_ros_prosilica.h.

std::string gazebo::GazeboRosProsilica::pollServiceName
private

ROS image topic name.

Definition at line 84 of file gazebo_ros_prosilica.h.

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

Definition at line 81 of file gazebo_ros_prosilica.h.

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

ros message

construct raw stereo message

Definition at line 80 of file gazebo_ros_prosilica.h.


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


gazebo_plugins
Author(s): John Hsu
autogenerated on Tue Apr 6 2021 02:19:40