37 #include <sensor_msgs/CameraInfo.h> 38 #include <sensor_msgs/Image.h> 39 #include <sensor_msgs/PointCloud2.h> 44 #include <dynamic_reconfigure/server.h> 45 #include "jsk_interactive_marker/CameraInfoPublisherConfig.h" 46 #include <yaml-cpp/yaml.h> 53 typedef std::shared_ptr<CameraInfoPublisher>
Ptr;
54 typedef jsk_interactive_marker::CameraInfoPublisherConfig
Config;
63 const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback);
66 const sensor_msgs::PointCloud2::ConstPtr& msg);
68 const sensor_msgs::Image::ConstPtr& msg);
79 std::shared_ptr <dynamic_reconfigure::Server<Config> >
srv_;
81 std::shared_ptr<interactive_markers::InteractiveMarkerServer>
server_;
std::shared_ptr< interactive_markers::InteractiveMarkerServer > server_
YAML::Node camera_info_yaml_
std::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
virtual void configCallback(Config &config, uint32_t level)
virtual ~CameraInfoPublisher()
std::shared_ptr< tf::TransformListener > tf_listener_
virtual void initializeInteractiveMarker()
virtual void processFeedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
virtual void publishCameraInfo(const ros::Time &stamp)
geometry_msgs::Pose latest_pose_
ros::Publisher pub_camera_info_
std::string parent_frame_id_
ros::Subscriber sub_sync_
virtual void staticRateCallback(const ros::TimerEvent &event)
std::shared_ptr< CameraInfoPublisher > Ptr
virtual void imageCallback(const sensor_msgs::Image::ConstPtr &msg)
jsk_interactive_marker::CameraInfoPublisherConfig Config
std::string yaml_filename_
virtual void pointcloudCallback(const sensor_msgs::PointCloud2::ConstPtr &msg)