|
void | addMarker (int id, double length, double x, double y, double z, double yaw, double pitch, double roll) |
|
void | alignObjPointsToCenter (Mat &obj_points, double ¢er_x, double ¢er_y, double ¢er_z) const |
|
void | callback (const sensor_msgs::ImageConstPtr &image, const sensor_msgs::CameraInfoConstPtr &cinfo, const aruco_pose::MarkerArrayConstPtr &markers) |
|
void | createGridBoard (ros::NodeHandle &nh) |
|
void | loadMap (std::string filename) |
|
virtual void | onInit () |
|
void | publishMapImage () |
|
void | publishMarkers () |
|
void | publishMarkersFrames () |
|
void | init (const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL) |
|
| Nodelet () |
|
virtual | ~Nodelet () |
|
Definition at line 59 of file aruco_map.cpp.
◆ addMarker()
void ArucoMap::addMarker |
( |
int |
id, |
|
|
double |
length, |
|
|
double |
x, |
|
|
double |
y, |
|
|
double |
z, |
|
|
double |
yaw, |
|
|
double |
pitch, |
|
|
double |
roll |
|
) |
| |
|
inline |
◆ alignObjPointsToCenter()
void ArucoMap::alignObjPointsToCenter |
( |
Mat & |
obj_points, |
|
|
double & |
center_x, |
|
|
double & |
center_y, |
|
|
double & |
center_z |
|
) |
| const |
|
inline |
◆ callback()
void ArucoMap::callback |
( |
const sensor_msgs::ImageConstPtr & |
image, |
|
|
const sensor_msgs::CameraInfoConstPtr & |
cinfo, |
|
|
const aruco_pose::MarkerArrayConstPtr & |
markers |
|
) |
| |
|
inline |
◆ createGridBoard()
◆ loadMap()
void ArucoMap::loadMap |
( |
std::string |
filename | ) |
|
|
inline |
◆ onInit()
virtual void ArucoMap::onInit |
( |
| ) |
|
|
inlinevirtual |
◆ publishMapImage()
void ArucoMap::publishMapImage |
( |
| ) |
|
|
inline |
◆ publishMarkers()
void ArucoMap::publishMarkers |
( |
| ) |
|
|
inline |
◆ publishMarkersFrames()
void ArucoMap::publishMarkersFrames |
( |
| ) |
|
|
inline |
◆ auto_flip_
bool ArucoMap::auto_flip_ |
|
private |
◆ board_
◆ br_
◆ camera_matrix_
Mat ArucoMap::camera_matrix_ |
|
private |
◆ debug_pub_
◆ dist_coeffs_
Mat ArucoMap::dist_coeffs_ |
|
private |
◆ image_axis_
bool ArucoMap::image_axis_ |
|
private |
◆ image_height_
int ArucoMap::image_height_ |
|
private |
◆ image_margin_
int ArucoMap::image_margin_ |
|
private |
◆ image_sub_
◆ image_width_
int ArucoMap::image_width_ |
|
private |
◆ img_pub_
◆ info_sub_
◆ known_tilt_
std::string ArucoMap::known_tilt_ |
|
private |
◆ map_
std::string ArucoMap::map_ |
|
private |
◆ markers_
aruco_pose::MarkerArray ArucoMap::markers_ |
|
private |
◆ markers_frame_
std::string ArucoMap::markers_frame_ |
|
private |
◆ markers_parent_frame_
std::string ArucoMap::markers_parent_frame_ |
|
private |
◆ markers_pub_
◆ markers_sub_
◆ markers_transforms_
vector<geometry_msgs::TransformStamped> ArucoMap::markers_transforms_ |
|
private |
◆ pose_
geometry_msgs::PoseWithCovarianceStamped ArucoMap::pose_ |
|
private |
◆ pose_pub_
◆ static_br_
◆ sync_
◆ tf_buffer_
◆ tf_listener_
◆ transform_
geometry_msgs::TransformStamped ArucoMap::transform_ |
|
private |
◆ vis_array_
visualization_msgs::MarkerArray ArucoMap::vis_array_ |
|
private |
◆ vis_markers_pub_
The documentation for this class was generated from the following file: