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

#include <gazebo_ros_camera_utils.h>

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

Public Member Functions

 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...
 

Protected Member Functions

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 ()
 

Protected Attributes

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_
 

Private Member Functions

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

Private Attributes

std::string camera_name_
 ROS camera name. More...
 
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 More...
 
sdf::ElementPtr sdf
 
std::string tf_prefix_
 tf prefix More...
 
ros::Subscriber trigger_subscriber_
 

Friends

class GazeboRosMultiCamera
 
class GazeboRosTriggeredMultiCamera
 

Detailed Description

Definition at line 57 of file gazebo_ros_camera_utils.h.

Constructor & Destructor Documentation

gazebo::GazeboRosCameraUtils::GazeboRosCameraUtils ( )

Constructor.

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

Definition at line 50 of file gazebo_ros_camera_utils.cpp.

gazebo::GazeboRosCameraUtils::~GazeboRosCameraUtils ( )

Destructor.

Definition at line 74 of file gazebo_ros_camera_utils.cpp.

Member Function Documentation

void gazebo::GazeboRosCameraUtils::CameraQueueThread ( )
protected

take care of callback queue

Definition at line 680 of file gazebo_ros_camera_utils.cpp.

bool gazebo::GazeboRosCameraUtils::CanTriggerCamera ( )
protectedvirtual

Reimplemented in gazebo::GazeboRosTriggeredCamera.

Definition at line 370 of file gazebo_ros_camera_utils.cpp.

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

Definition at line 61 of file gazebo_ros_camera_utils.cpp.

void gazebo::GazeboRosCameraUtils::ImageConnect ( )
protected

Definition at line 402 of file gazebo_ros_camera_utils.cpp.

void gazebo::GazeboRosCameraUtils::ImageDisconnect ( )
protected

Definition at line 416 of file gazebo_ros_camera_utils.cpp.

void gazebo::GazeboRosCameraUtils::InfoConnect ( )
private

Keep track of number of connctions for CameraInfo.

void gazebo::GazeboRosCameraUtils::InfoDisconnect ( )
private
void gazebo::GazeboRosCameraUtils::Init ( )
private

Compute camera_ parameters if set to 0

Definition at line 431 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 104 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 86 of file gazebo_ros_camera_utils.cpp.

void gazebo::GazeboRosCameraUtils::LoadThread ( )
private

Definition at line 264 of file gazebo_ros_camera_utils.cpp.

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

Definition at line 257 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 666 of file gazebo_ros_camera_utils.cpp.

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

Definition at line 641 of file gazebo_ros_camera_utils.cpp.

void gazebo::GazeboRosCameraUtils::PublishCameraInfo ( )
protected

Definition at line 650 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 615 of file gazebo_ros_camera_utils.cpp.

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

Definition at line 608 of file gazebo_ros_camera_utils.cpp.

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

: Camera modification functions

Definition at line 383 of file gazebo_ros_camera_utils.cpp.

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

Definition at line 394 of file gazebo_ros_camera_utils.cpp.

void gazebo::GazeboRosCameraUtils::TriggerCamera ( )
protectedvirtual

Reimplemented in gazebo::GazeboRosTriggeredCamera.

Definition at line 366 of file gazebo_ros_camera_utils.cpp.

void gazebo::GazeboRosCameraUtils::TriggerCameraInternal ( const std_msgs::Empty::ConstPtr &  dummy)
private

Definition at line 375 of file gazebo_ros_camera_utils.cpp.

Friends And Related Function Documentation

friend class GazeboRosMultiCamera
friend

Definition at line 226 of file gazebo_ros_camera_utils.h.

friend class GazeboRosTriggeredMultiCamera
friend

Definition at line 227 of file gazebo_ros_camera_utils.h.

Member Data Documentation

bool gazebo::GazeboRosCameraUtils::border_crop_
protected

Definition at line 160 of file gazebo_ros_camera_utils.h.

boost::thread gazebo::GazeboRosCameraUtils::callback_queue_thread_
protected

Definition at line 186 of file gazebo_ros_camera_utils.h.

rendering::CameraPtr gazebo::GazeboRosCameraUtils::camera_
protected

Definition at line 194 of file gazebo_ros_camera_utils.h.

boost::shared_ptr<camera_info_manager::CameraInfoManager> gazebo::GazeboRosCameraUtils::camera_info_manager_
protected

Definition at line 162 of file gazebo_ros_camera_utils.h.

ros::Publisher gazebo::GazeboRosCameraUtils::camera_info_pub_
protected

camera info

Definition at line 137 of file gazebo_ros_camera_utils.h.

std::string gazebo::GazeboRosCameraUtils::camera_info_topic_name_
protected

Definition at line 138 of file gazebo_ros_camera_utils.h.

std::string gazebo::GazeboRosCameraUtils::camera_name_
private

ROS camera name.

Definition at line 121 of file gazebo_ros_camera_utils.h.

ros::CallbackQueue gazebo::GazeboRosCameraUtils::camera_queue_
protected

Definition at line 184 of file gazebo_ros_camera_utils.h.

ros::Subscriber gazebo::GazeboRosCameraUtils::cameraHFOVSubscriber_
private

Definition at line 173 of file gazebo_ros_camera_utils.h.

ros::Subscriber gazebo::GazeboRosCameraUtils::cameraUpdateRateSubscriber_
private

Definition at line 174 of file gazebo_ros_camera_utils.h.

double gazebo::GazeboRosCameraUtils::cx_
protected

Definition at line 150 of file gazebo_ros_camera_utils.h.

double gazebo::GazeboRosCameraUtils::cx_prime_
protected

Definition at line 149 of file gazebo_ros_camera_utils.h.

double gazebo::GazeboRosCameraUtils::cy_
protected

Definition at line 151 of file gazebo_ros_camera_utils.h.

boost::thread gazebo::GazeboRosCameraUtils::deferred_load_thread_
private

Definition at line 209 of file gazebo_ros_camera_utils.h.

unsigned int gazebo::GazeboRosCameraUtils::depth_
protected

Definition at line 190 of file gazebo_ros_camera_utils.h.

double gazebo::GazeboRosCameraUtils::distortion_k1_
protected

Definition at line 154 of file gazebo_ros_camera_utils.h.

double gazebo::GazeboRosCameraUtils::distortion_k2_
protected

Definition at line 155 of file gazebo_ros_camera_utils.h.

double gazebo::GazeboRosCameraUtils::distortion_k3_
protected

Definition at line 156 of file gazebo_ros_camera_utils.h.

double gazebo::GazeboRosCameraUtils::distortion_t1_
protected

Definition at line 157 of file gazebo_ros_camera_utils.h.

double gazebo::GazeboRosCameraUtils::distortion_t2_
protected

Definition at line 158 of file gazebo_ros_camera_utils.h.

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

Definition at line 180 of file gazebo_ros_camera_utils.h.

double gazebo::GazeboRosCameraUtils::focal_length_
protected

Definition at line 152 of file gazebo_ros_camera_utils.h.

std::string gazebo::GazeboRosCameraUtils::format_
protected

Definition at line 191 of file gazebo_ros_camera_utils.h.

std::string gazebo::GazeboRosCameraUtils::frame_name_
protected

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 143 of file gazebo_ros_camera_utils.h.

double gazebo::GazeboRosCameraUtils::hack_baseline_
protected

Definition at line 153 of file gazebo_ros_camera_utils.h.

unsigned int gazebo::GazeboRosCameraUtils::height_
protected

Definition at line 190 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 93 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 95 of file gazebo_ros_camera_utils.h.

sensor_msgs::Image gazebo::GazeboRosCameraUtils::image_msg_
protected

ROS image message.

Definition at line 115 of file gazebo_ros_camera_utils.h.

image_transport::Publisher gazebo::GazeboRosCameraUtils::image_pub_
protected

Definition at line 111 of file gazebo_ros_camera_utils.h.

std::string gazebo::GazeboRosCameraUtils::image_topic_name_
protected

ROS image topic name.

Definition at line 127 of file gazebo_ros_camera_utils.h.

bool gazebo::GazeboRosCameraUtils::initialized_
protected

True if camera util is initialized.

Definition at line 224 of file gazebo_ros_camera_utils.h.

image_transport::ImageTransport* gazebo::GazeboRosCameraUtils::itnode_
private

Definition at line 112 of file gazebo_ros_camera_utils.h.

common::Time gazebo::GazeboRosCameraUtils::last_info_update_time_
protected

Definition at line 139 of file gazebo_ros_camera_utils.h.

common::Time gazebo::GazeboRosCameraUtils::last_update_time_
protected

Definition at line 147 of file gazebo_ros_camera_utils.h.

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

Definition at line 210 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 167 of file gazebo_ros_camera_utils.h.

event::ConnectionPtr gazebo::GazeboRosCameraUtils::newFrameConnection_
private

Definition at line 199 of file gazebo_ros_camera_utils.h.

sensors::SensorPtr gazebo::GazeboRosCameraUtils::parentSensor_
protected

Definition at line 193 of file gazebo_ros_camera_utils.h.

std::string gazebo::GazeboRosCameraUtils::robot_namespace_
private

for setting ROS name space

Definition at line 118 of file gazebo_ros_camera_utils.h.

ros::NodeHandle* gazebo::GazeboRosCameraUtils::rosnode_
protected

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

Definition at line 110 of file gazebo_ros_camera_utils.h.

sdf::ElementPtr gazebo::GazeboRosCameraUtils::sdf
private

Definition at line 207 of file gazebo_ros_camera_utils.h.

common::Time gazebo::GazeboRosCameraUtils::sensor_update_time_
protected

Definition at line 201 of file gazebo_ros_camera_utils.h.

int gazebo::GazeboRosCameraUtils::skip_
protected

Definition at line 171 of file gazebo_ros_camera_utils.h.

std::string gazebo::GazeboRosCameraUtils::tf_prefix_
private

tf prefix

Definition at line 124 of file gazebo_ros_camera_utils.h.

ros::Subscriber gazebo::GazeboRosCameraUtils::trigger_subscriber_
private

Definition at line 218 of file gazebo_ros_camera_utils.h.

std::string gazebo::GazeboRosCameraUtils::trigger_topic_name_
protected

ROS trigger topic name.

Definition at line 221 of file gazebo_ros_camera_utils.h.

std::string gazebo::GazeboRosCameraUtils::type_
protected

size of image buffer

Definition at line 170 of file gazebo_ros_camera_utils.h.

double gazebo::GazeboRosCameraUtils::update_period_
protected

Definition at line 146 of file gazebo_ros_camera_utils.h.

double gazebo::GazeboRosCameraUtils::update_rate_
protected

update rate of this sensor

Definition at line 145 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 102 of file gazebo_ros_camera_utils.h.

unsigned int gazebo::GazeboRosCameraUtils::width_
protected

Definition at line 190 of file gazebo_ros_camera_utils.h.

physics::WorldPtr gazebo::GazeboRosCameraUtils::world
protected

Definition at line 204 of file gazebo_ros_camera_utils.h.

physics::WorldPtr gazebo::GazeboRosCameraUtils::world_
protected

Definition at line 197 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 Tue Mar 26 2019 02:31:27