Public Member Functions | Protected Member Functions | List of all members
gazebo::GazeboRosThermalCamera_< Base > Class Template Reference

#include <gazebo_ros_thermal_camera.h>

Inheritance diagram for gazebo::GazeboRosThermalCamera_< Base >:
Inheritance graph
[legend]

Public Member Functions

 GazeboRosThermalCamera_ ()
 Constructor. More...
 
void Load (sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
 Load the plugin. More...
 
template<>
void LoadImpl (sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
 
template<>
void LoadImpl (sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
 
void LoadImpl (sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
 
 ~GazeboRosThermalCamera_ ()
 Destructor. More...
 
- Public Member Functions inherited from Base
virtual void saySomething ()=0
 

Protected Member Functions

virtual void OnNewFrame (const unsigned char *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format)
 Update the controller. More...
 
virtual void OnNewImageFrame (const unsigned char *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format)
 Update the controller. More...
 
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)
 

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

Detailed Description

template<typename Base>
class gazebo::GazeboRosThermalCamera_< Base >

Definition at line 62 of file gazebo_ros_thermal_camera.h.

Constructor & Destructor Documentation

Constructor.

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

Definition at line 68 of file gazebo_ros_thermal_camera.cpp.

Destructor.

Definition at line 75 of file gazebo_ros_thermal_camera.cpp.

Member Function Documentation

template<class Base >
void gazebo::GazeboRosThermalCamera_< Base >::Load ( sensors::SensorPtr  _parent,
sdf::ElementPtr  _sdf 
)

Load the plugin.

Parameters
takein SDF root element

Definition at line 80 of file gazebo_ros_thermal_camera.cpp.

template<>
void gazebo::GazeboRosThermalCamera_< DepthCameraPlugin >::LoadImpl ( sensors::SensorPtr  _parent,
sdf::ElementPtr  _sdf 
)

Definition at line 38 of file gazebo_ros_thermal_depth_camera_plugin.cpp.

template<>
void gazebo::GazeboRosThermalCamera_< CameraPlugin >::LoadImpl ( sensors::SensorPtr  _parent,
sdf::ElementPtr  _sdf 
)

Definition at line 38 of file gazebo_ros_thermal_camera_plugin.cpp.

template<typename Base >
void gazebo::GazeboRosThermalCamera_< Base >::LoadImpl ( sensors::SensorPtr  _parent,
sdf::ElementPtr  _sdf 
)
inline

Definition at line 74 of file gazebo_ros_thermal_camera.h.

template<class Base >
void gazebo::GazeboRosThermalCamera_< Base >::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 103 of file gazebo_ros_thermal_camera.cpp.

template<class Base >
void gazebo::GazeboRosThermalCamera_< Base >::OnNewImageFrame ( const unsigned char *  _image,
unsigned int  _width,
unsigned int  _height,
unsigned int  _depth,
const std::string &  _format 
)
protectedvirtual

Update the controller.

Definition at line 142 of file gazebo_ros_thermal_camera.cpp.

template<class Base >
void gazebo::GazeboRosThermalCamera_< Base >::PutCameraData ( const unsigned char *  _src)
protected

Put camera data to the ROS topic.

don't bother if there are no subscribers

Definition at line 159 of file gazebo_ros_thermal_camera.cpp.

template<class Base >
void gazebo::GazeboRosThermalCamera_< Base >::PutCameraData ( const unsigned char *  _src,
common::Time &  last_update_time 
)
protected

Definition at line 152 of file gazebo_ros_thermal_camera.cpp.


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


hector_gazebo_thermal_camera
Author(s): Stefan Kohlbrecher
autogenerated on Fri Feb 5 2021 03:48:36