#include <gazebo_ros_camera_utils.h>

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::CameraInfoManager > | camera_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::NodeHandle * | rosnode_ |
| 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::ImageTransport * | itnode_ |
| 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 |
Definition at line 57 of file gazebo_ros_camera_utils.h.
| gazebo::GazeboRosCameraUtils::GazeboRosCameraUtils | ( | ) |
Constructor.
| parent | The 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.
|
protected |
take care of callback queue
Definition at line 676 of file gazebo_ros_camera_utils.cpp.
|
protectedvirtual |
Reimplemented in gazebo::GazeboRosTriggeredCamera.
Definition at line 370 of file gazebo_ros_camera_utils.cpp.
|
private |
Definition at line 61 of file gazebo_ros_camera_utils.cpp.
|
protected |
Definition at line 398 of file gazebo_ros_camera_utils.cpp.
|
protected |
Definition at line 412 of file gazebo_ros_camera_utils.cpp.
|
private |
Keep track of number of connctions for CameraInfo.
|
private |
|
private |
Compute camera_ parameters if set to 0
Definition at line 427 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.
| [in] | _parent | Take in SDF root element. |
| [in] | _sdf | SDF values. |
| [in] | _camera_name_suffix | required 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.
| [in] | _parent | Take in SDF root element. |
| [in] | _sdf | SDF values. |
| [in] | _camera_name_suffix | Suffix of the camera name. |
| [in] | _hack_baseline | Multiple camera baseline. |
Definition at line 86 of file gazebo_ros_camera_utils.cpp.
|
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.
|
protected |
Publish CameraInfo to the ROS topic.
Definition at line 662 of file gazebo_ros_camera_utils.cpp.
|
protected |
Definition at line 637 of file gazebo_ros_camera_utils.cpp.
|
protected |
Definition at line 646 of file gazebo_ros_camera_utils.cpp.
|
protected |
Put camera data to the ROS topic.
don't bother if there are no subscribers
Definition at line 611 of file gazebo_ros_camera_utils.cpp.
|
protected |
Definition at line 604 of file gazebo_ros_camera_utils.cpp.
|
private |
: Camera modification functions
Definition at line 383 of file gazebo_ros_camera_utils.cpp.
|
private |
Definition at line 390 of file gazebo_ros_camera_utils.cpp.
|
protectedvirtual |
Reimplemented in gazebo::GazeboRosTriggeredCamera.
Definition at line 366 of file gazebo_ros_camera_utils.cpp.
|
private |
Definition at line 375 of file gazebo_ros_camera_utils.cpp.
|
friend |
Definition at line 226 of file gazebo_ros_camera_utils.h.
|
friend |
Definition at line 227 of file gazebo_ros_camera_utils.h.
|
protected |
Definition at line 160 of file gazebo_ros_camera_utils.h.
|
protected |
Definition at line 186 of file gazebo_ros_camera_utils.h.
|
protected |
Definition at line 194 of file gazebo_ros_camera_utils.h.
|
protected |
Definition at line 162 of file gazebo_ros_camera_utils.h.
|
protected |
camera info
Definition at line 137 of file gazebo_ros_camera_utils.h.
|
protected |
Definition at line 138 of file gazebo_ros_camera_utils.h.
|
private |
ROS camera name.
Definition at line 121 of file gazebo_ros_camera_utils.h.
|
protected |
Definition at line 184 of file gazebo_ros_camera_utils.h.
|
private |
Definition at line 173 of file gazebo_ros_camera_utils.h.
|
private |
Definition at line 174 of file gazebo_ros_camera_utils.h.
|
protected |
Definition at line 150 of file gazebo_ros_camera_utils.h.
|
protected |
Definition at line 149 of file gazebo_ros_camera_utils.h.
|
protected |
Definition at line 151 of file gazebo_ros_camera_utils.h.
|
private |
Definition at line 209 of file gazebo_ros_camera_utils.h.
|
protected |
Definition at line 190 of file gazebo_ros_camera_utils.h.
|
protected |
Definition at line 154 of file gazebo_ros_camera_utils.h.
|
protected |
Definition at line 155 of file gazebo_ros_camera_utils.h.
|
protected |
Definition at line 156 of file gazebo_ros_camera_utils.h.
|
protected |
Definition at line 157 of file gazebo_ros_camera_utils.h.
|
protected |
Definition at line 158 of file gazebo_ros_camera_utils.h.
|
private |
Definition at line 180 of file gazebo_ros_camera_utils.h.
|
protected |
Definition at line 152 of file gazebo_ros_camera_utils.h.
|
protected |
Definition at line 191 of file gazebo_ros_camera_utils.h.
|
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.
|
protected |
Definition at line 153 of file gazebo_ros_camera_utils.h.
|
protected |
Definition at line 190 of file gazebo_ros_camera_utils.h.
|
protected |
Keep track of number of image connections.
Definition at line 93 of file gazebo_ros_camera_utils.h.
|
protected |
A mutex to lock access to image_connect_count_.
Definition at line 95 of file gazebo_ros_camera_utils.h.
|
protected |
ROS image message.
Definition at line 115 of file gazebo_ros_camera_utils.h.
|
protected |
Definition at line 111 of file gazebo_ros_camera_utils.h.
|
protected |
ROS image topic name.
Definition at line 127 of file gazebo_ros_camera_utils.h.
|
protected |
True if camera util is initialized.
Definition at line 224 of file gazebo_ros_camera_utils.h.
|
private |
Definition at line 112 of file gazebo_ros_camera_utils.h.
|
protected |
Definition at line 139 of file gazebo_ros_camera_utils.h.
|
protected |
Definition at line 147 of file gazebo_ros_camera_utils.h.
|
private |
Definition at line 210 of file gazebo_ros_camera_utils.h.
|
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.
|
private |
Definition at line 199 of file gazebo_ros_camera_utils.h.
|
protected |
Definition at line 193 of file gazebo_ros_camera_utils.h.
|
private |
for setting ROS name space
Definition at line 118 of file gazebo_ros_camera_utils.h.
|
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.
|
private |
Definition at line 207 of file gazebo_ros_camera_utils.h.
|
protected |
Definition at line 201 of file gazebo_ros_camera_utils.h.
|
protected |
Definition at line 171 of file gazebo_ros_camera_utils.h.
|
private |
tf prefix
Definition at line 124 of file gazebo_ros_camera_utils.h.
|
private |
Definition at line 218 of file gazebo_ros_camera_utils.h.
|
protected |
ROS trigger topic name.
Definition at line 221 of file gazebo_ros_camera_utils.h.
|
protected |
size of image buffer
Definition at line 170 of file gazebo_ros_camera_utils.h.
|
protected |
Definition at line 146 of file gazebo_ros_camera_utils.h.
|
protected |
update rate of this sensor
Definition at line 145 of file gazebo_ros_camera_utils.h.
|
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.
|
protected |
Definition at line 190 of file gazebo_ros_camera_utils.h.
|
protected |
Definition at line 204 of file gazebo_ros_camera_utils.h.
|
protected |
Definition at line 197 of file gazebo_ros_camera_utils.h.