Go to the documentation of this file.
18 #ifndef GAZEBO_ROS_CAMERA_UTILS_HH
19 #define GAZEBO_ROS_CAMERA_UTILS_HH
23 #include <boost/thread.hpp>
24 #include <boost/thread/mutex.hpp>
32 #include <sensor_msgs/PointCloud.h>
33 #include <sensor_msgs/Image.h>
34 #include <sensor_msgs/CameraInfo.h>
35 #include <std_msgs/Empty.h>
36 #include <std_msgs/Float64.h>
41 #include <gazebo_plugins/GazeboRosCameraConfig.h>
42 #include <dynamic_reconfigure/server.h>
45 #include <gazebo/physics/physics.hh>
46 #include <gazebo/transport/TransportTypes.hh>
47 #include <gazebo/msgs/MessageTypes.hh>
48 #include <gazebo/common/Time.hh>
49 #include <gazebo/sensors/SensorTypes.hh>
54 class GazeboRosMultiCamera;
55 class GazeboRosTriggeredMultiCamera;
69 public:
void Load(sensors::SensorPtr _parent,
71 const std::string &_camera_name_suffix =
"");
78 public:
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf,
79 const std::string &_camera_name_suffix,
80 double _hack_baseline);
82 public: event::ConnectionPtr
OnLoad(
const boost::function<
void()>&);
89 common::Time &last_update_time);
104 private:
void SetHFOV(
const std_msgs::Float64::ConstPtr& hfov);
105 private:
void SetUpdateRate(
const std_msgs::Float64::ConstPtr& update_rate);
179 dynamic_reconfigure::Server<gazebo_plugins::GazeboRosCameraConfig>
181 void configCallback(gazebo_plugins::GazeboRosCameraConfig &config,
207 private: sdf::ElementPtr
sdf;
bool initialized_
True if camera util is initialized.
image_transport::ImageTransport * itnode_
image_transport::Publisher image_pub_
sensors::SensorPtr parentSensor_
virtual bool CanTriggerCamera()
boost::thread callback_queue_thread_
void PutCameraData(const unsigned char *_src)
Put camera data to the ROS topic.
ros::Publisher camera_info_pub_
camera info
event::EventT< void()> load_event_
common::Time last_update_time_
void InfoConnect()
Keep track of number of connctions for CameraInfo.
ros::Subscriber cameraUpdateRateSubscriber_
void SetUpdateRate(const std_msgs::Float64::ConstPtr &update_rate)
std::string image_topic_name_
ROS image topic name.
ros::NodeHandle * rosnode_
A pointer to the ROS node. A node will be instantiated if it does not exist.
common::Time last_info_update_time_
std::string robot_namespace_
for setting ROS name space
boost::shared_ptr< boost::mutex > image_connect_count_lock_
A mutex to lock access to image_connect_count_.
std::string type_
size of image buffer
std::string frame_name_
ROS frame transform name to use in the image message header. This should typically match the link nam...
void SetHFOV(const std_msgs::Float64::ConstPtr &hfov)
: Camera modification functions
virtual void TriggerCamera()
boost::shared_ptr< int > image_connect_count_
Keep track of number of image connections.
ros::Subscriber cameraHFOVSubscriber_
common::Time sensor_update_time_
GazeboRosCameraUtils()
Constructor.
ros::Subscriber trigger_subscriber_
boost::mutex lock_
A mutex to lock access to fields that are used in ROS message callbacks.
boost::thread deferred_load_thread_
void configCallback(gazebo_plugins::GazeboRosCameraConfig &config, uint32_t level)
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf, const std::string &_camera_name_suffix="")
Load the plugin.
boost::shared_ptr< camera_info_manager::CameraInfoManager > camera_info_manager_
dynamic_reconfigure::Server< gazebo_plugins::GazeboRosCameraConfig > * dyn_srv_
event::ConnectionPtr newFrameConnection_
boost::shared_ptr< bool > was_active_
Keep track when we activate this camera through ros subscription, was it already active?...
double update_rate_
update rate of this sensor
std::string camera_name_
ROS camera name.
~GazeboRosCameraUtils()
Destructor.
sensor_msgs::Image image_msg_
ROS image message.
void TriggerCameraInternal(const std_msgs::Empty::ConstPtr &dummy)
std::string camera_info_topic_name_
ros::CallbackQueue camera_queue_
rendering::CameraPtr camera_
event::ConnectionPtr OnLoad(const boost::function< void()> &)
std::string tf_prefix_
tf prefix
std::string trigger_topic_name_
ROS trigger topic name.
gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Sep 5 2024 02:49:55