Public Member Functions | Protected Member Functions | Protected Attributes | Friends | List of all members
gazebo::GazeboRosTriggeredCamera Class Reference

#include <gazebo_ros_triggered_camera.h>

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

Public Member Functions

 GazeboRosTriggeredCamera ()
 Constructor. More...
 
void Load (sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
 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...
 
void SetCameraEnabled (const bool _enabled)
 
 ~GazeboRosTriggeredCamera ()
 Destructor. More...
 

Protected Member Functions

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

Protected Attributes

std::mutex mutex
 
event::ConnectionPtr preRenderConnection_
 
int triggered = 0
 

Friends

class GazeboRosTriggeredMultiCamera
 

Additional Inherited Members

- 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 ()
 
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)
 
- 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 32 of file gazebo_ros_triggered_camera.h.

Constructor & Destructor Documentation

gazebo::GazeboRosTriggeredCamera::GazeboRosTriggeredCamera ( )

Constructor.

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

Definition at line 35 of file gazebo_ros_triggered_camera.cpp.

gazebo::GazeboRosTriggeredCamera::~GazeboRosTriggeredCamera ( )

Destructor.

Definition at line 41 of file gazebo_ros_triggered_camera.cpp.

Member Function Documentation

bool gazebo::GazeboRosTriggeredCamera::CanTriggerCamera ( )
protectedvirtual

Reimplemented from gazebo::GazeboRosCameraUtils.

Definition at line 113 of file gazebo_ros_triggered_camera.cpp.

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

Load the plugin.

Parameters
takein SDF root element

Definition at line 46 of file gazebo_ros_triggered_camera.cpp.

void gazebo::GazeboRosTriggeredCamera::Load ( sensors::SensorPtr  _parent,
sdf::ElementPtr  _sdf,
const std::string &  _camera_name_suffix,
double  _hack_baseline 
)

Load the plugin.

Parameters
[in]_parentTake in SDF root element.
[in]_sdfSDF values.
[in]_camera_name_suffixSuffix of the camera name.
[in]_hack_baselineMultiple camera baseline.

Definition at line 73 of file gazebo_ros_triggered_camera.cpp.

void gazebo::GazeboRosTriggeredCamera::OnNewFrame ( const unsigned char *  _image,
unsigned int  _width,
unsigned int  _height,
unsigned int  _depth,
const std::string &  _format 
)
protectedvirtual

Update the controller.

Definition at line 88 of file gazebo_ros_triggered_camera.cpp.

void gazebo::GazeboRosTriggeredCamera::PreRender ( )
protected

Definition at line 118 of file gazebo_ros_triggered_camera.cpp.

void gazebo::GazeboRosTriggeredCamera::SetCameraEnabled ( const bool  _enabled)

Definition at line 127 of file gazebo_ros_triggered_camera.cpp.

void gazebo::GazeboRosTriggeredCamera::TriggerCamera ( )
protectedvirtual

Reimplemented from gazebo::GazeboRosCameraUtils.

Definition at line 105 of file gazebo_ros_triggered_camera.cpp.

Friends And Related Function Documentation

friend class GazeboRosTriggeredMultiCamera
friend

Definition at line 73 of file gazebo_ros_triggered_camera.h.

Member Data Documentation

std::mutex gazebo::GazeboRosTriggeredCamera::mutex
protected

Definition at line 71 of file gazebo_ros_triggered_camera.h.

event::ConnectionPtr gazebo::GazeboRosTriggeredCamera::preRenderConnection_
protected

Definition at line 63 of file gazebo_ros_triggered_camera.h.

int gazebo::GazeboRosTriggeredCamera::triggered = 0
protected

Definition at line 69 of file gazebo_ros_triggered_camera.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