ROS Node. More...
#include <laser_robot_calibration_node.h>
Public Member Functions | |
void | callbackLaser (const sensor_msgs::LaserScan::ConstPtr &msg) |
void | callbackMarker (const geometry_msgs::PoseArray::ConstPtr &msg) |
LaserRobotCalibrationNode (ros::NodeHandle &n) | |
void | stateMashine () |
Private Types | |
enum | States { INIT, ROTATE_TO_MARKER, ROTATE_NORMAL_TO_MARKER } |
Private Member Functions | |
void | draw_debug_view () |
void | rotateToMarkerNearPoint (cv::Point2f anchor) |
Static Private Member Functions | |
static void | mouseCallBack (int evt, int c, int r, int flags, void *param) |
Private Attributes | |
cv::Point2f | anchor_ |
unsigned | callbackCount |
cv::Mat | debug_view_ |
cv::Vec3f | marker_ |
cv::Matx< float, 3, 3 > | Mr2v_ |
geometry_msgs::PoseArray | msg_marker_ |
sensor_msgs::LaserScan | msg_scan_ |
ros::NodeHandle | n_ |
ros::NodeHandle | n_param_ |
ros::Publisher | pub_cmd_ |
States | state_ |
ros::Subscriber | sub_laser_ |
ros::Subscriber | sub_marker_ |
ROS Node.
Definition at line 43 of file laser_robot_calibration_node.h.
enum LaserRobotCalibrationNode::States [private] |
Definition at line 45 of file laser_robot_calibration_node.h.
Definition at line 68 of file laser_robot_calibration_node.cpp.
void LaserRobotCalibrationNode::callbackLaser | ( | const sensor_msgs::LaserScan::ConstPtr & | msg | ) |
Definition at line 78 of file laser_robot_calibration_node.cpp.
void LaserRobotCalibrationNode::callbackMarker | ( | const geometry_msgs::PoseArray::ConstPtr & | msg | ) |
Definition at line 82 of file laser_robot_calibration_node.cpp.
void LaserRobotCalibrationNode::draw_debug_view | ( | ) | [private] |
Definition at line 87 of file laser_robot_calibration_node.cpp.
static void LaserRobotCalibrationNode::mouseCallBack | ( | int | evt, |
int | c, | ||
int | r, | ||
int | flags, | ||
void * | param | ||
) | [inline, static, private] |
Definition at line 71 of file laser_robot_calibration_node.h.
void LaserRobotCalibrationNode::rotateToMarkerNearPoint | ( | cv::Point2f | anchor | ) | [private] |
Definition at line 132 of file laser_robot_calibration_node.cpp.
Definition at line 137 of file laser_robot_calibration_node.cpp.
cv::Point2f LaserRobotCalibrationNode::anchor_ [private] |
Definition at line 67 of file laser_robot_calibration_node.h.
unsigned LaserRobotCalibrationNode::callbackCount [private] |
Definition at line 58 of file laser_robot_calibration_node.h.
cv::Mat LaserRobotCalibrationNode::debug_view_ [private] |
Definition at line 62 of file laser_robot_calibration_node.h.
cv::Vec3f LaserRobotCalibrationNode::marker_ [private] |
Definition at line 68 of file laser_robot_calibration_node.h.
cv::Matx<float, 3, 3 > LaserRobotCalibrationNode::Mr2v_ [private] |
Definition at line 44 of file laser_robot_calibration_node.h.
geometry_msgs::PoseArray LaserRobotCalibrationNode::msg_marker_ [private] |
Definition at line 64 of file laser_robot_calibration_node.h.
sensor_msgs::LaserScan LaserRobotCalibrationNode::msg_scan_ [private] |
Definition at line 63 of file laser_robot_calibration_node.h.
ros::NodeHandle LaserRobotCalibrationNode::n_ [private] |
Definition at line 56 of file laser_robot_calibration_node.h.
Definition at line 57 of file laser_robot_calibration_node.h.
Definition at line 61 of file laser_robot_calibration_node.h.
States LaserRobotCalibrationNode::state_ [private] |
Definition at line 69 of file laser_robot_calibration_node.h.
Definition at line 59 of file laser_robot_calibration_node.h.
Definition at line 60 of file laser_robot_calibration_node.h.