Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes | Friends
gazebo::GazeboRosCameraUtils Class Reference

#include <gazebo_ros_camera_utils.h>

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

List of all members.

Public Member Functions

 GazeboRosCameraUtils ()
 Constructor.
void Load (sensors::SensorPtr _parent, sdf::ElementPtr _sdf, const std::string &_camera_name_suffix="")
 Load the plugin.
void Load (sensors::SensorPtr _parent, sdf::ElementPtr _sdf, const std::string &_camera_name_suffix, double _hack_baseline)
 Load the plugin.
event::ConnectionPtr OnLoad (const boost::function< void()> &)
 ~GazeboRosCameraUtils ()
 Destructor.

Protected Member Functions

void CameraQueueThread ()
void ImageConnect ()
void ImageDisconnect ()
void PublishCameraInfo (ros::Publisher camera_info_publisher)
 Publish CameraInfo to the ROS topic.
void PublishCameraInfo (common::Time &last_update_time)
void PublishCameraInfo ()
void PutCameraData (const unsigned char *_src)
 Put camera data to the ROS topic.
void PutCameraData (const unsigned char *_src, common::Time &last_update_time)

Protected Attributes

boost::thread callback_queue_thread_
rendering::CameraPtr camera_
boost::shared_ptr
< camera_info_manager::CameraInfoManager
camera_info_manager_
ros::Publisher camera_info_pub_
 camera info
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.
double hack_baseline_
unsigned int height_
boost::shared_ptr< int > image_connect_count_
 Keep track of number of image connections.
boost::shared_ptr< boost::mutex > image_connect_count_lock_
 A mutex to lock access to image_connect_count_.
sensor_msgs::Image image_msg_
 ROS image message.
image_transport::Publisher image_pub_
std::string image_topic_name_
 ROS image topic name.
bool initialized_
 True if camera util is initialized.
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.
sensors::SensorPtr parentSensor_
ros::NodeHandlerosnode_
 A pointer to the ROS node. A node will be instantiated if it does not exist.
common::Time sensor_update_time_
int skip_
std::string type_
 size of image buffer
double update_period_
double update_rate_
 update rate of this sensor
boost::shared_ptr< bool > was_active_
 Keep track when we activate this camera through ros subscription, was it already active? resume state when unsubscribed.
unsigned int width_
physics::WorldPtr world
physics::WorldPtr world_

Private Member Functions

void configCallback (gazebo_plugins::GazeboRosCameraConfig &config, uint32_t level)
void InfoConnect ()
 Keep track of number of connctions for CameraInfo.
void InfoDisconnect ()
void Init ()
void LoadThread ()
void SetHFOV (const std_msgs::Float64::ConstPtr &hfov)
 : Camera modification functions
void SetUpdateRate (const std_msgs::Float64::ConstPtr &update_rate)

Private Attributes

std::string camera_name_
 ROS camera name.
ros::Subscriber cameraHFOVSubscriber_
ros::Subscriber cameraUpdateRateSubscriber_
boost::thread deferred_load_thread_
dynamic_reconfigure::Server
< gazebo_plugins::GazeboRosCameraConfig > * 
dyn_srv_
image_transport::ImageTransportitnode_
event::EventT< void()> load_event_
event::ConnectionPtr newFrameConnection_
std::string robot_namespace_
 for setting ROS name space
sdf::ElementPtr sdf
std::string tf_prefix_
 tf prefix

Friends

class GazeboRosMultiCamera

Detailed Description

Definition at line 55 of file gazebo_ros_camera_utils.h.


Constructor & Destructor Documentation

Constructor.

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

Definition at line 49 of file gazebo_ros_camera_utils.cpp.

Destructor.

Definition at line 73 of file gazebo_ros_camera_utils.cpp.


Member Function Documentation

take care of callback queue

Definition at line 658 of file gazebo_ros_camera_utils.cpp.

void gazebo::GazeboRosCameraUtils::configCallback ( gazebo_plugins::GazeboRosCameraConfig &  config,
uint32_t  level 
) [private]

Definition at line 60 of file gazebo_ros_camera_utils.cpp.

Definition at line 376 of file gazebo_ros_camera_utils.cpp.

Definition at line 390 of file gazebo_ros_camera_utils.cpp.

Keep track of number of connctions for CameraInfo.

Reimplemented in gazebo::GazeboRosDepthCamera.

Reimplemented in gazebo::GazeboRosDepthCamera.

Compute camera_ parameters if set to 0

Definition at line 405 of file gazebo_ros_camera_utils.cpp.

void gazebo::GazeboRosCameraUtils::Load ( sensors::SensorPtr  _parent,
sdf::ElementPtr  _sdf,
const std::string _camera_name_suffix = "" 
)

Load the plugin.

Parameters:
[in]_parentTake in SDF root element.
[in]_sdfSDF values.
[in]_camera_name_suffixrequired before calling LoadThread

Definition at line 103 of file gazebo_ros_camera_utils.cpp.

void gazebo::GazeboRosCameraUtils::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 85 of file gazebo_ros_camera_utils.cpp.

Definition at line 263 of file gazebo_ros_camera_utils.cpp.

event::ConnectionPtr gazebo::GazeboRosCameraUtils::OnLoad ( const boost::function< void()> &  load_function)

Definition at line 256 of file gazebo_ros_camera_utils.cpp.

void gazebo::GazeboRosCameraUtils::PublishCameraInfo ( ros::Publisher  camera_info_publisher) [protected]

Publish CameraInfo to the ROS topic.

Definition at line 644 of file gazebo_ros_camera_utils.cpp.

void gazebo::GazeboRosCameraUtils::PublishCameraInfo ( common::Time &  last_update_time) [protected]

Definition at line 615 of file gazebo_ros_camera_utils.cpp.

void gazebo::GazeboRosCameraUtils::PutCameraData ( const unsigned char *  _src) [protected]

Put camera data to the ROS topic.

don't bother if there are no subscribers

Definition at line 589 of file gazebo_ros_camera_utils.cpp.

void gazebo::GazeboRosCameraUtils::PutCameraData ( const unsigned char *  _src,
common::Time &  last_update_time 
) [protected]

Definition at line 582 of file gazebo_ros_camera_utils.cpp.

void gazebo::GazeboRosCameraUtils::SetHFOV ( const std_msgs::Float64::ConstPtr &  hfov) [private]

: Camera modification functions

Definition at line 357 of file gazebo_ros_camera_utils.cpp.

void gazebo::GazeboRosCameraUtils::SetUpdateRate ( const std_msgs::Float64::ConstPtr &  update_rate) [private]

Definition at line 368 of file gazebo_ros_camera_utils.cpp.


Friends And Related Function Documentation

friend class GazeboRosMultiCamera [friend]

Definition at line 211 of file gazebo_ros_camera_utils.h.


Member Data Documentation

Definition at line 182 of file gazebo_ros_camera_utils.h.

rendering::CameraPtr gazebo::GazeboRosCameraUtils::camera_ [protected]

Definition at line 190 of file gazebo_ros_camera_utils.h.

Definition at line 158 of file gazebo_ros_camera_utils.h.

camera info

Definition at line 135 of file gazebo_ros_camera_utils.h.

Definition at line 136 of file gazebo_ros_camera_utils.h.

ROS camera name.

Definition at line 119 of file gazebo_ros_camera_utils.h.

Definition at line 180 of file gazebo_ros_camera_utils.h.

Definition at line 169 of file gazebo_ros_camera_utils.h.

Definition at line 170 of file gazebo_ros_camera_utils.h.

Definition at line 148 of file gazebo_ros_camera_utils.h.

Definition at line 147 of file gazebo_ros_camera_utils.h.

Definition at line 149 of file gazebo_ros_camera_utils.h.

Definition at line 205 of file gazebo_ros_camera_utils.h.

unsigned int gazebo::GazeboRosCameraUtils::depth_ [protected]

Definition at line 186 of file gazebo_ros_camera_utils.h.

Definition at line 152 of file gazebo_ros_camera_utils.h.

Definition at line 153 of file gazebo_ros_camera_utils.h.

Definition at line 154 of file gazebo_ros_camera_utils.h.

Definition at line 155 of file gazebo_ros_camera_utils.h.

Definition at line 156 of file gazebo_ros_camera_utils.h.

dynamic_reconfigure::Server<gazebo_plugins::GazeboRosCameraConfig>* gazebo::GazeboRosCameraUtils::dyn_srv_ [private]

Definition at line 176 of file gazebo_ros_camera_utils.h.

Definition at line 150 of file gazebo_ros_camera_utils.h.

Definition at line 187 of file gazebo_ros_camera_utils.h.

ROS frame transform name to use in the image message header. This should typically match the link name the sensor is attached.

Definition at line 141 of file gazebo_ros_camera_utils.h.

Definition at line 151 of file gazebo_ros_camera_utils.h.

unsigned int gazebo::GazeboRosCameraUtils::height_ [protected]

Definition at line 186 of file gazebo_ros_camera_utils.h.

boost::shared_ptr<int> gazebo::GazeboRosCameraUtils::image_connect_count_ [protected]

Keep track of number of image connections.

Definition at line 91 of file gazebo_ros_camera_utils.h.

boost::shared_ptr<boost::mutex> gazebo::GazeboRosCameraUtils::image_connect_count_lock_ [protected]

A mutex to lock access to image_connect_count_.

Definition at line 93 of file gazebo_ros_camera_utils.h.

sensor_msgs::Image gazebo::GazeboRosCameraUtils::image_msg_ [protected]

ROS image message.

Definition at line 113 of file gazebo_ros_camera_utils.h.

Definition at line 109 of file gazebo_ros_camera_utils.h.

ROS image topic name.

Definition at line 125 of file gazebo_ros_camera_utils.h.

True if camera util is initialized.

Definition at line 209 of file gazebo_ros_camera_utils.h.

Definition at line 110 of file gazebo_ros_camera_utils.h.

Definition at line 137 of file gazebo_ros_camera_utils.h.

Definition at line 145 of file gazebo_ros_camera_utils.h.

event::EventT<void()> gazebo::GazeboRosCameraUtils::load_event_ [private]

Definition at line 206 of file gazebo_ros_camera_utils.h.

boost::mutex gazebo::GazeboRosCameraUtils::lock_ [protected]

A mutex to lock access to fields that are used in ROS message callbacks.

Definition at line 163 of file gazebo_ros_camera_utils.h.

Definition at line 195 of file gazebo_ros_camera_utils.h.

sensors::SensorPtr gazebo::GazeboRosCameraUtils::parentSensor_ [protected]

Definition at line 189 of file gazebo_ros_camera_utils.h.

for setting ROS name space

Definition at line 116 of file gazebo_ros_camera_utils.h.

A pointer to the ROS node. A node will be instantiated if it does not exist.

Definition at line 108 of file gazebo_ros_camera_utils.h.

sdf::ElementPtr gazebo::GazeboRosCameraUtils::sdf [private]

Definition at line 203 of file gazebo_ros_camera_utils.h.

Definition at line 197 of file gazebo_ros_camera_utils.h.

Definition at line 167 of file gazebo_ros_camera_utils.h.

tf prefix

Definition at line 122 of file gazebo_ros_camera_utils.h.

size of image buffer

Definition at line 166 of file gazebo_ros_camera_utils.h.

Definition at line 144 of file gazebo_ros_camera_utils.h.

update rate of this sensor

Definition at line 143 of file gazebo_ros_camera_utils.h.

boost::shared_ptr<bool> gazebo::GazeboRosCameraUtils::was_active_ [protected]

Keep track when we activate this camera through ros subscription, was it already active? resume state when unsubscribed.

Definition at line 100 of file gazebo_ros_camera_utils.h.

unsigned int gazebo::GazeboRosCameraUtils::width_ [protected]

Definition at line 186 of file gazebo_ros_camera_utils.h.

physics::WorldPtr gazebo::GazeboRosCameraUtils::world [protected]

Definition at line 200 of file gazebo_ros_camera_utils.h.

physics::WorldPtr gazebo::GazeboRosCameraUtils::world_ [protected]

Definition at line 193 of file gazebo_ros_camera_utils.h.


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


gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Jun 6 2019 18:41:10