Public Member Functions | Private Attributes | List of all members
throttling_camera::ThrottlingCamera Class Reference
Inheritance diagram for throttling_camera::ThrottlingCamera:
Inheritance graph
[legend]

Public Member Functions

void Load (gazebo::sensors::SensorPtr parent, sdf::ElementPtr sdf) override
 
void OnNewFrame (const unsigned char *image, unsigned int width, unsigned int height, unsigned int depth, const std::string &format) override
 
 ThrottlingCamera ()=default
 
 ~ThrottlingCamera () override=default
 

Private Attributes

gazebo::sensors::SensorPtr camPtr
 
double maxUpdateInterval
 
gazebo::physics::PresetManagerPtr presetManager
 
std::unique_ptr< AverageStat > timeSamples
 
gazebo::physics::WorldPtr world
 
- Private Attributes inherited from gazebo::GazeboRosCameraUtils
bool auto_distortion_
 
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_
 
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_
 
double hack_baseline_
 
unsigned int height_
 
boost::shared_ptr< int > image_connect_count_
 
boost::shared_ptr< boost::mutex > image_connect_count_lock_
 
sensor_msgs::Image image_msg_
 
image_transport::Publisher image_pub_
 
std::string image_topic_name_
 
bool initialized_
 
common::Time last_info_update_time_
 
common::Time last_update_time_
 
boost::mutex lock_
 
sensors::SensorPtr parentSensor_
 
ros::NodeHandlerosnode_
 
common::Time sensor_update_time_
 
int skip_
 
std::string trigger_topic_name_
 
std::string type_
 
double update_period_
 
double update_rate_
 
boost::shared_ptr< bool > was_active_
 
unsigned int width_
 
physics::WorldPtr world
 
physics::WorldPtr world_
 

Additional Inherited Members

- Private Member Functions inherited from gazebo::GazeboRosCameraUtils
 GazeboRosCameraUtils ()
 
void Load (sensors::SensorPtr _parent, sdf::ElementPtr _sdf, const std::string &_camera_name_suffix="")
 
void Load (sensors::SensorPtr _parent, sdf::ElementPtr _sdf, const std::string &_camera_name_suffix, double _hack_baseline)
 
event::ConnectionPtr OnLoad (const boost::function< void()> &)
 
 ~GazeboRosCameraUtils ()
 
void CameraQueueThread ()
 
virtual bool CanTriggerCamera ()
 
void ImageConnect ()
 
void ImageDisconnect ()
 
void PublishCameraInfo ()
 
void PublishCameraInfo (ros::Publisher camera_info_publisher)
 
void PublishCameraInfo (common::Time &last_update_time)
 
void PutCameraData (const unsigned char *_src)
 
void PutCameraData (const unsigned char *_src, common::Time &last_update_time)
 
virtual void TriggerCamera ()
 

Detailed Description

Gazebo camera plugin for a world-throttling (rate-preserving) camera.

This plugin will slow the simulation down to maintain average publishing rate. Note that this plugin will only perform slowdown, it will not speed the simulation back up!

Definition at line 112 of file throttling_camera.cpp.

Constructor & Destructor Documentation

◆ ThrottlingCamera()

throttling_camera::ThrottlingCamera::ThrottlingCamera ( )
default

◆ ~ThrottlingCamera()

throttling_camera::ThrottlingCamera::~ThrottlingCamera ( )
overridedefault

Member Function Documentation

◆ Load()

void throttling_camera::ThrottlingCamera::Load ( gazebo::sensors::SensorPtr  parent,
sdf::ElementPtr  sdf 
)
inlineoverride

Plugin load function. Called by Gazebo each time the plugin is instantiated.

Parameters
parentGazebo sensor that this plugin connects to.
sdfSDF element containing this plugin.

Definition at line 137 of file throttling_camera.cpp.

◆ OnNewFrame()

void throttling_camera::ThrottlingCamera::OnNewFrame ( const unsigned char *  image,
unsigned int  width,
unsigned int  height,
unsigned int  depth,
const std::string &  format 
)
inlineoverride

Frame callback. Called every time a new frame is rendered by the camera.

Checks whether we should slow simulation down and publishes a new image message.

Parameters
imageImage data.
widthImage width, in pixels.
heightImage height, in pixels.
depthImage depth, in bytes.
formatImage format description string.

Definition at line 210 of file throttling_camera.cpp.

Member Data Documentation

◆ camPtr

gazebo::sensors::SensorPtr throttling_camera::ThrottlingCamera::camPtr
private

A pointer to the Gazebo camera sensor.

Definition at line 116 of file throttling_camera.cpp.

◆ maxUpdateInterval

double throttling_camera::ThrottlingCamera::maxUpdateInterval
private

Maximum update interval that is considered "okay". Should be higher than the "average" update interval to avoid extreme slowdowns

Definition at line 123 of file throttling_camera.cpp.

◆ presetManager

gazebo::physics::PresetManagerPtr throttling_camera::ThrottlingCamera::presetManager
private

A pointer to the physics preset manager. Used to actually slow the simulation down.

Definition at line 120 of file throttling_camera.cpp.

◆ timeSamples

std::unique_ptr<AverageStat> throttling_camera::ThrottlingCamera::timeSamples
private

Statistics for publishing time intervals.

Definition at line 126 of file throttling_camera.cpp.

◆ world

gazebo::physics::WorldPtr throttling_camera::ThrottlingCamera::world
private

A pointer to the current simulated world (required to change world parameters)

Definition at line 118 of file throttling_camera.cpp.


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


clover_simulation
Author(s): Alexey Rogachevskiy, Andrey Ryabov, Arthur Golubtsov, Oleg Kalachev, Svyatoslav Zhuravlev
autogenerated on Mon Feb 28 2022 22:08:36