$search

gazebo::GazeboRosThermalCamera Class Reference
[Ros Camera Plugin XML Reference and Example]

GazeboRosThermalCamera Controller. More...

#include <gazebo_ros_thermal_camera.h>

List of all members.

Public Member Functions

 GazeboRosThermalCamera (Entity *parent)
 Constructor.
virtual ~GazeboRosThermalCamera ()
 Destructor.

Public Attributes

 EIGEN_MAKE_ALIGNED_OPERATOR_NEW

Protected Member Functions

virtual void FiniChild ()
 Finalize the controller, unadvertise topics.
virtual void InitChild ()
 Init the controller.
virtual void LoadChild (XMLConfigNode *node)
 Load the controller.
virtual void UpdateChild ()
 Update the controller.

Private Member Functions

void CameraQueueThread ()
void configCallback (hector_gazebo_thermal_camera::GazeboRosThermalCameraConfig &config, uint32_t level)
void convertImageFormat (unsigned char *dst, const unsigned char *src)
bool fillDepthImage (pcl::PointCloud< pcl::PointXYZ > &point_cloud, uint32_t rows_arg, uint32_t cols_arg, uint32_t step_arg, void *data_arg)
void ImageConnect ()
void ImageDisconnect ()
void InfoConnect ()
void InfoDisconnect ()
void PointCloudConnect ()
void PointCloudDisconnect ()
void PublishCameraInfo ()
 Publish CameraInfo to the ROS topic.
void PutCameraData ()
 Put camera data to the ROS topic.
void SetHFOV (const std_msgs::Float64::ConstPtr &hfov)
void SetUpdateRate (const std_msgs::Float64::ConstPtr &update_rate)

Private Attributes

boost::thread callback_queue_thread_
ros::Publisher camera_info_pub_
ros::CallbackQueue camera_queue_
ros::Subscriber cameraHFOVSubscriber_
sensor_msgs::CameraInfo cameraInfoMsg
std::string cameraInfoTopicName
 ROS camera_info topic name.
ParamT< std::string > * cameraInfoTopicNameP
std::string cameraName
 ROS camera name.
ParamT< std::string > * cameraNameP
ros::Subscriber cameraUpdateRateSubscriber_
double Cx
ParamT< double > * CxP
double CxPrime
ParamT< double > * CxPrimeP
double Cy
ParamT< double > * CyP
int depth
double distortion_k1
ParamT< double > * distortion_k1P
double distortion_k2
ParamT< double > * distortion_k2P
double distortion_k3
ParamT< double > * distortion_k3P
double distortion_t1
ParamT< double > * distortion_t1P
double distortion_t2
ParamT< double > * distortion_t2P
dynamic_reconfigure::Server
< hector_gazebo_thermal_camera::GazeboRosThermalCameraConfig > * 
dyn_srv_
std::string dynamicReconfigureName
double focal_length
ParamT< double > * focal_lengthP
std::string frameName
 ROS frame transform name to use in the image message header. This should typically match the link name the sensor is attached.
ParamT< std::string > * frameNameP
double hack_baseline
ParamT< double > * hack_baselineP
int height
 size of image buffer
image_transport::Publisher image_pub_
int imageConnectCount
 Keep track of number of connctions.
sensor_msgs::Image imageMsg
 ROS image message.
std::string imageTopicName
 ROS image topic name.
ParamT< std::string > * imageTopicNameP
 Parameters.
int infoConnectCount
 Keep track of number of connctions for CameraInfo.
image_transport::ImageTransportitnode_
Time last_camera_info_pub_time_
Time last_image_pub_time_
Time last_point_cloud_pub_time_
boost::mutex lock
 A mutex to lock access to fields that are used in ROS message callbacks.
nodelet::Loadermanager_
ros::NodeHandlemanagernode_
MonoCameraSensor * myParent
 A pointer to the parent camera sensor.
ros::Publisher point_cloud_pub_
int pointCloudConnectCount
 Keep track of number of connctions for point clouds.
double pointCloudCutoff
ParamT< double > * pointCloudCutoffP
pcl::PointCloud< pcl::PointXYZ > pointCloudMsg
std::string pointCloudTopicName
 ROS point cloud topic name.
ParamT< std::string > * pointCloudTopicNameP
std::string robotNamespace
ParamT< std::string > * robotNamespaceP
 for setting ROS name space
ros::NodeHandlerosnode_
 A pointer to the ROS node. A node will be instantiated if it does not exist.
int skip
std::string type
int width

Detailed Description

GazeboRosThermalCamera Controller.

Definition at line 134 of file gazebo_ros_thermal_camera.h.


Constructor & Destructor Documentation

gazebo::GazeboRosThermalCamera::GazeboRosThermalCamera ( Entity *  parent  ) 

Constructor.

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

Definition at line 87 of file gazebo_ros_thermal_camera.cpp.

gazebo::GazeboRosThermalCamera::~GazeboRosThermalCamera (  )  [virtual]

Destructor.

Definition at line 137 of file gazebo_ros_thermal_camera.cpp.


Member Function Documentation

void gazebo::GazeboRosThermalCamera::CameraQueueThread (  )  [private]

Definition at line 820 of file gazebo_ros_thermal_camera.cpp.

void gazebo::GazeboRosThermalCamera::configCallback ( hector_gazebo_thermal_camera::GazeboRosThermalCameraConfig &  config,
uint32_t  level 
) [private]

Definition at line 128 of file gazebo_ros_thermal_camera.cpp.

void gazebo::GazeboRosThermalCamera::convertImageFormat ( unsigned char *  dst,
const unsigned char *  src 
) [private]

Definition at line 589 of file gazebo_ros_thermal_camera.cpp.

bool gazebo::GazeboRosThermalCamera::fillDepthImage ( pcl::PointCloud< pcl::PointXYZ > &  point_cloud,
uint32_t  rows_arg,
uint32_t  cols_arg,
uint32_t  step_arg,
void *  data_arg 
) [private]

Definition at line 697 of file gazebo_ros_thermal_camera.cpp.

void gazebo::GazeboRosThermalCamera::FiniChild (  )  [protected, virtual]

Finalize the controller, unadvertise topics.

Definition at line 445 of file gazebo_ros_thermal_camera.cpp.

void gazebo::GazeboRosThermalCamera::ImageConnect (  )  [private]

Definition at line 297 of file gazebo_ros_thermal_camera.cpp.

void gazebo::GazeboRosThermalCamera::ImageDisconnect (  )  [private]

Definition at line 304 of file gazebo_ros_thermal_camera.cpp.

void gazebo::GazeboRosThermalCamera::InfoConnect (  )  [private]

Definition at line 270 of file gazebo_ros_thermal_camera.cpp.

void gazebo::GazeboRosThermalCamera::InfoDisconnect (  )  [private]

Definition at line 276 of file gazebo_ros_thermal_camera.cpp.

void gazebo::GazeboRosThermalCamera::InitChild (  )  [protected, virtual]

Init the controller.

Compute camera parameters if set to 0

Definition at line 340 of file gazebo_ros_thermal_camera.cpp.

void gazebo::GazeboRosThermalCamera::LoadChild ( XMLConfigNode *  node  )  [protected, virtual]

Load the controller.

Parameters:
node XML config node

Definition at line 162 of file gazebo_ros_thermal_camera.cpp.

void gazebo::GazeboRosThermalCamera::PointCloudConnect (  )  [private]

Definition at line 318 of file gazebo_ros_thermal_camera.cpp.

void gazebo::GazeboRosThermalCamera::PointCloudDisconnect (  )  [private]

Definition at line 326 of file gazebo_ros_thermal_camera.cpp.

void gazebo::GazeboRosThermalCamera::PublishCameraInfo (  )  [private]

Publish CameraInfo to the ROS topic.

Definition at line 758 of file gazebo_ros_thermal_camera.cpp.

void gazebo::GazeboRosThermalCamera::PutCameraData (  )  [private]

Put camera data to the ROS topic.

Todo:
: don't bother if there are no subscribers

copy from depth to pointCloudMsg

Definition at line 461 of file gazebo_ros_thermal_camera.cpp.

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

Definition at line 283 of file gazebo_ros_thermal_camera.cpp.

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

Definition at line 290 of file gazebo_ros_thermal_camera.cpp.

void gazebo::GazeboRosThermalCamera::UpdateChild (  )  [protected, virtual]

Update the controller.

publish CameraInfo

Definition at line 425 of file gazebo_ros_thermal_camera.cpp.


Member Data Documentation

Definition at line 273 of file gazebo_ros_thermal_camera.h.

Definition at line 192 of file gazebo_ros_thermal_camera.h.

Definition at line 271 of file gazebo_ros_thermal_camera.h.

Definition at line 256 of file gazebo_ros_thermal_camera.h.

Definition at line 198 of file gazebo_ros_thermal_camera.h.

ROS camera_info topic name.

Definition at line 229 of file gazebo_ros_thermal_camera.h.

Definition at line 203 of file gazebo_ros_thermal_camera.h.

ROS camera name.

Definition at line 225 of file gazebo_ros_thermal_camera.h.

ParamT<std::string>* gazebo::GazeboRosThermalCamera::cameraNameP [private]

Definition at line 205 of file gazebo_ros_thermal_camera.h.

Definition at line 257 of file gazebo_ros_thermal_camera.h.

Definition at line 237 of file gazebo_ros_thermal_camera.h.

ParamT<double>* gazebo::GazeboRosThermalCamera::CxP [private]

Definition at line 209 of file gazebo_ros_thermal_camera.h.

Definition at line 236 of file gazebo_ros_thermal_camera.h.

ParamT<double>* gazebo::GazeboRosThermalCamera::CxPrimeP [private]

Definition at line 208 of file gazebo_ros_thermal_camera.h.

Definition at line 238 of file gazebo_ros_thermal_camera.h.

ParamT<double>* gazebo::GazeboRosThermalCamera::CyP [private]

Definition at line 210 of file gazebo_ros_thermal_camera.h.

Definition at line 252 of file gazebo_ros_thermal_camera.h.

Definition at line 242 of file gazebo_ros_thermal_camera.h.

Definition at line 214 of file gazebo_ros_thermal_camera.h.

Definition at line 243 of file gazebo_ros_thermal_camera.h.

Definition at line 215 of file gazebo_ros_thermal_camera.h.

Definition at line 244 of file gazebo_ros_thermal_camera.h.

Definition at line 216 of file gazebo_ros_thermal_camera.h.

Definition at line 245 of file gazebo_ros_thermal_camera.h.

Definition at line 217 of file gazebo_ros_thermal_camera.h.

Definition at line 246 of file gazebo_ros_thermal_camera.h.

Definition at line 218 of file gazebo_ros_thermal_camera.h.

dynamic_reconfigure::Server<hector_gazebo_thermal_camera::GazeboRosThermalCameraConfig>* gazebo::GazeboRosThermalCamera::dyn_srv_ [private]

Definition at line 263 of file gazebo_ros_thermal_camera.h.

Definition at line 268 of file gazebo_ros_thermal_camera.h.

Definition at line 276 of file gazebo_ros_thermal_camera.h.

Definition at line 239 of file gazebo_ros_thermal_camera.h.

Definition at line 211 of file gazebo_ros_thermal_camera.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 234 of file gazebo_ros_thermal_camera.h.

ParamT<std::string>* gazebo::GazeboRosThermalCamera::frameNameP [private]

Definition at line 206 of file gazebo_ros_thermal_camera.h.

Definition at line 240 of file gazebo_ros_thermal_camera.h.

Definition at line 212 of file gazebo_ros_thermal_camera.h.

size of image buffer

Definition at line 252 of file gazebo_ros_thermal_camera.h.

Definition at line 193 of file gazebo_ros_thermal_camera.h.

Keep track of number of connctions.

Definition at line 162 of file gazebo_ros_thermal_camera.h.

ROS image message.

Definition at line 197 of file gazebo_ros_thermal_camera.h.

ROS image topic name.

Definition at line 227 of file gazebo_ros_thermal_camera.h.

ParamT<std::string>* gazebo::GazeboRosThermalCamera::imageTopicNameP [private]

Parameters.

Definition at line 202 of file gazebo_ros_thermal_camera.h.

Keep track of number of connctions for CameraInfo.

Definition at line 172 of file gazebo_ros_thermal_camera.h.

Definition at line 194 of file gazebo_ros_thermal_camera.h.

Definition at line 260 of file gazebo_ros_thermal_camera.h.

Definition at line 260 of file gazebo_ros_thermal_camera.h.

Definition at line 260 of file gazebo_ros_thermal_camera.h.

boost::mutex gazebo::GazeboRosThermalCamera::lock [private]

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

Definition at line 249 of file gazebo_ros_thermal_camera.h.

Definition at line 191 of file gazebo_ros_thermal_camera.h.

Definition at line 190 of file gazebo_ros_thermal_camera.h.

MonoCameraSensor* gazebo::GazeboRosThermalCamera::myParent [private]

A pointer to the parent camera sensor.

Definition at line 186 of file gazebo_ros_thermal_camera.h.

Definition at line 192 of file gazebo_ros_thermal_camera.h.

Keep track of number of connctions for point clouds.

Definition at line 167 of file gazebo_ros_thermal_camera.h.

Definition at line 241 of file gazebo_ros_thermal_camera.h.

Definition at line 213 of file gazebo_ros_thermal_camera.h.

pcl::PointCloud<pcl::PointXYZ> gazebo::GazeboRosThermalCamera::pointCloudMsg [private]

Definition at line 199 of file gazebo_ros_thermal_camera.h.

ROS point cloud topic name.

Definition at line 231 of file gazebo_ros_thermal_camera.h.

Definition at line 204 of file gazebo_ros_thermal_camera.h.

Definition at line 222 of file gazebo_ros_thermal_camera.h.

ParamT<std::string>* gazebo::GazeboRosThermalCamera::robotNamespaceP [private]

for setting ROS name space

Definition at line 221 of file gazebo_ros_thermal_camera.h.

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

Definition at line 189 of file gazebo_ros_thermal_camera.h.

Definition at line 254 of file gazebo_ros_thermal_camera.h.

std::string gazebo::GazeboRosThermalCamera::type [private]

Definition at line 253 of file gazebo_ros_thermal_camera.h.

Definition at line 252 of file gazebo_ros_thermal_camera.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


hector_gazebo_thermal_camera
Author(s): Stefan Kohlbrecher
autogenerated on Tue Mar 5 13:31:17 2013