32 #ifndef TUW_ELLIPSES_NODE_H 33 #define TUW_ELLIPSES_NODE_H 39 #include <dynamic_reconfigure/server.h> 40 #include <tuw_ellipses/EllipsesDetectionConfig.h> 41 #include <boost/date_time/posix_time/posix_time.hpp> 44 #include <marker_msgs/FiducialDetection.h> 45 #include <marker_msgs/MarkerDetection.h> 54 void update(
const unsigned long &counter);
55 void callbackParameters (tuw_ellipses::EllipsesDetectionConfig &config, uint32_t level );
58 dynamic_reconfigure::Server<tuw_ellipses::EllipsesDetectionConfig>::CallbackType
reconfigureFnc_;
74 void imageCallback(
const sensor_msgs::ImageConstPtr& image_msg,
75 const sensor_msgs::CameraInfoConstPtr& info_msg);
102 #endif //TUW_ELLIPSES_NODE_H dynamic_reconfigure::Server< tuw_ellipses::EllipsesDetectionConfig > reconfigureServer_
ros::Publisher pub_perceptions_
const ParametersNode * param()
dynamic_reconfigure::Server< tuw_ellipses::EllipsesDetectionConfig >::CallbackType reconfigureFnc_
tf::TransformBroadcaster transformBroadcaster_
boost::posix_time::ptime timeCallbackReceivedLast_
boost::posix_time::ptime timeDetectionStart_
unsigned long callback_counter_
std::list< tf::StampedTransform > markerTransforms_
boost::posix_time::ptime timeDetectionEnd_
void imageCallback(const sensor_msgs::ImageConstPtr &image_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
ros::Publisher pub_fiducials_
sensor_msgs::CameraInfoConstPtr camera_info_
boost::posix_time::ptime timeCallbackReceived_
int show_camera_image_waitkey
ros::Publisher pub_ellipses_
cv_bridge::CvImagePtr image_mono_
image_transport::CameraSubscriber sub_camera_
void createTransforms(const std_msgs::Header &header)
image_transport::ImageTransport imageTransport_
void callbackParameters(tuw_ellipses::EllipsesDetectionConfig &config, uint32_t level)
void update(const unsigned long &counter)