#include <artoolkitplus.h>
Classes | |
| class | Parameter |
Public Member Functions | |
| ARToolKitPlusNode (ros::NodeHandle &n) | |
| ~ARToolKitPlusNode () | |
Private Member Functions | |
| void | callbackParameters (tuw_artoolkitplus::ARParamConfig &config, uint32_t level) |
| void | estimatePoses (const std_msgs::Header &header) |
| void | generateDebugImage (cv::Mat &img) |
| void | imageCallback (const sensor_msgs::ImageConstPtr &image_msg, const sensor_msgs::CameraInfoConstPtr &info_msg) |
| void | init () |
| void | initTrackerMultiMarker (const sensor_msgs::CameraInfoConstPtr &camer_info_) |
| void | initTrackerSingleMarker (const sensor_msgs::CameraInfoConstPtr &camer_info_) |
| void | matrix2Tf (const ARFloat M[3][4], tf::Transform &transform) |
| void | publishMarkers (const std_msgs::Header &header) |
| void | publishPerceptions (const std_msgs::Header &header) |
| void | publishTf () |
| void | readParam () |
| void | updateParameterTrackerMultiMarker (const sensor_msgs::CameraInfoConstPtr &camer_info) |
| void | updateParameterTrackerSingleMarker (const sensor_msgs::CameraInfoConstPtr &camer_info) |
Private Attributes | |
| const ARToolKitPlus::ARMultiMarkerInfoT * | arMultiMarkerInfo_ |
| std::vector< ARToolKitPlus::ARTag2D > | arTags2D_ |
| int | callback_counter_ |
| image_transport::CameraSubscriber | cameraSubscriber_ |
| image_transport::ImageTransport | imageTransport_ |
| MyLogger * | logger_ |
| std::list< tf::StampedTransform > | markerTransforms_ |
| std::vector< int > | markerTransformsID_ |
| ros::NodeHandle | n_ |
| ros::NodeHandle | n_param_ |
| Parameter | param_ |
| ros::Publisher | pub_markers_ |
| ros::Publisher | pub_perceptions_ |
| dynamic_reconfigure::Server< tuw_artoolkitplus::ARParamConfig >::CallbackType | reconfigureFnc_ |
| dynamic_reconfigure::Server< tuw_artoolkitplus::ARParamConfig > | reconfigureServer_ |
| boost::shared_ptr< ARToolKitPlus::TrackerMultiMarker > | trackerMultiMarker_ |
| boost::shared_ptr< ARToolKitPlus::TrackerSingleMarker > | trackerSingleMarker_ |
| tf::TransformBroadcaster | transformBroadcaster_ |
Definition at line 71 of file artoolkitplus.h.
| ARToolKitPlusNode::ARToolKitPlusNode | ( | ros::NodeHandle & | n | ) |
Definition at line 42 of file artoolkitplus.cpp.
| ARToolKitPlusNode::~ARToolKitPlusNode | ( | ) |
Definition at line 55 of file artoolkitplus.cpp.
|
private |
Definition at line 105 of file artoolkitplus_node.cpp.
|
private |
Definition at line 316 of file artoolkitplus.cpp.
|
private |
Definition at line 24 of file artoolkitplus_draw.cpp.
|
private |
Sort out marker which are part of multi marker patterns
Definition at line 254 of file artoolkitplus.cpp.
|
private |
Definition at line 382 of file artoolkitplus.cpp.
|
private |
Definition at line 136 of file artoolkitplus.cpp.
|
private |
Definition at line 153 of file artoolkitplus.cpp.
|
private |
Definition at line 33 of file artoolkitplus_node.cpp.
|
private |
Definition at line 49 of file artoolkitplus_node.cpp.
|
private |
Definition at line 84 of file artoolkitplus_node.cpp.
|
private |
Definition at line 43 of file artoolkitplus_node.cpp.
|
private |
|
private |
Definition at line 211 of file artoolkitplus.cpp.
|
private |
Definition at line 169 of file artoolkitplus.cpp.
|
private |
Definition at line 101 of file artoolkitplus.h.
|
private |
Definition at line 98 of file artoolkitplus.h.
|
private |
Definition at line 92 of file artoolkitplus.h.
|
private |
Definition at line 94 of file artoolkitplus.h.
|
private |
Definition at line 93 of file artoolkitplus.h.
|
private |
Definition at line 102 of file artoolkitplus.h.
|
private |
Definition at line 99 of file artoolkitplus.h.
|
private |
Definition at line 100 of file artoolkitplus.h.
|
private |
Definition at line 90 of file artoolkitplus.h.
|
private |
Definition at line 91 of file artoolkitplus.h.
|
private |
Definition at line 103 of file artoolkitplus.h.
|
private |
Definition at line 105 of file artoolkitplus.h.
|
private |
Definition at line 104 of file artoolkitplus.h.
|
private |
Definition at line 126 of file artoolkitplus.h.
|
private |
Definition at line 125 of file artoolkitplus.h.
|
private |
Definition at line 97 of file artoolkitplus.h.
|
private |
Definition at line 96 of file artoolkitplus.h.
|
private |
Definition at line 95 of file artoolkitplus.h.