College of DuPage Lunabotics Documentation
2025
|
Provides localization using AprilTags and manages an action server for localization feedback. More...
Public Types | |
using | Localization = lunabot_msgs::action::Localization |
using | GoalHandleLocalization = rclcpp_action::ServerGoalHandle< Localization > |
Public Member Functions | |
LocalizationServer () | |
Constructor for the LocalizationServer class. More... | |
Private Member Functions | |
rclcpp_action::GoalResponse | handle_goal (const rclcpp_action::GoalUUID &, std::shared_ptr< const Localization::Goal >) |
Handles goal requests from clients. More... | |
rclcpp_action::CancelResponse | handle_cancel (const std::shared_ptr< GoalHandleLocalization >) |
Handles cancellation requests from clients. More... | |
void | handle_accepted (const std::shared_ptr< GoalHandleLocalization > goal_handle) |
Accepts and starts the goal execution. More... | |
void | execute (const std::shared_ptr< GoalHandleLocalization > goal_handle) |
Executes the localization process. More... | |
void | localize () |
Aligns the robot to face east with the D455 camera facing AprilTag with tag 7. More... | |
void | d455_detect_apriltag (const sensor_msgs::msg::Image::SharedPtr input_image) |
Detects AprilTags in images from the D455 camera. More... | |
void | d456_detect_apriltag (const sensor_msgs::msg::Image::SharedPtr input_image) |
Detects AprilTags in images from the D456 camera. More... | |
void | process_apriltag (const sensor_msgs::msg::Image::SharedPtr &input_image, bool &tag_7_detected_, bool &tag_11_detected_, const rclcpp::Publisher< sensor_msgs::msg::Image >::SharedPtr &overlay_publisher, bool calculate_tag_) |
Processes detected AprilTags, calculates pose, and publishes overlay image. More... | |
double | normalize_angle (double angle) |
Normalizes an angle to the range [-pi, pi]. More... | |
void | calculate_distances (const cv::Vec3d &tvec, double &lateral_distance, double &depth_distance) |
Calculates lateral and depth distances from translation vector. More... | |
void | calculate_yaw (const cv::Vec3d &rvec, double &tag_7_yaw_) |
Calculates yaw from rotation vector. More... | |
Private Attributes | |
bool | d455_tag_7_detected_ |
bool | d455_tag_11_detected_ |
bool | d456_tag_7_detected_ |
bool | d456_tag_11_detected_ |
bool | turn_direction_set_ |
bool | turn_clockwise_ |
bool | timer_started_ |
bool | success_ |
double | lateral_distance_ |
double | depth_distance_ |
double | tag_7_yaw_ |
rclcpp::Time | start_time_ |
rclcpp::TimerBase::SharedPtr | localization_timer_ |
geometry_msgs::msg::Twist | twist |
rclcpp_action::Server< Localization >::SharedPtr | action_server_ |
rclcpp::Subscription< sensor_msgs::msg::Image >::SharedPtr | d455_image_subscriber_ |
rclcpp::Subscription< sensor_msgs::msg::Image >::SharedPtr | d456_image_subscriber_ |
rclcpp::Publisher< sensor_msgs::msg::Image >::SharedPtr | d455_overlay_publisher_ |
rclcpp::Publisher< sensor_msgs::msg::Image >::SharedPtr | d456_overlay_publisher_ |
rclcpp::Publisher< geometry_msgs::msg::Twist >::SharedPtr | cmd_vel_publisher_ |
Provides localization using AprilTags and manages an action server for localization feedback.
using LocalizationServer::GoalHandleLocalization = rclcpp_action::ServerGoalHandle<Localization> |
using LocalizationServer::Localization = lunabot_msgs::action::Localization |
|
inline |
Constructor for the LocalizationServer class.
|
inlineprivate |
Calculates lateral and depth distances from translation vector.
tvec | Translation vector. |
lateral_distance | Calculated lateral distance. |
depth_distance | Calculated depth distance. |
|
inlineprivate |
Calculates yaw from rotation vector.
rvec | Rotation vector. |
tag_7_yaw_ | Calculated yaw for tag_7. |
|
inlineprivate |
Detects AprilTags in images from the D455 camera.
input_image | Image message from the D455 camera. |
|
inlineprivate |
Detects AprilTags in images from the D456 camera.
input_image | Image message from the D456 camera. |
|
inlineprivate |
Executes the localization process.
goal_handle | Handle for the current goal. |
|
inlineprivate |
Accepts and starts the goal execution.
goal_handle | Handle for the current goal. |
|
inlineprivate |
Handles cancellation requests from clients.
|
inlineprivate |
Handles goal requests from clients.
|
inlineprivate |
Aligns the robot to face east with the D455 camera facing AprilTag with tag 7.
|
inlineprivate |
Normalizes an angle to the range [-pi, pi].
angle | The angle to normalize. |
|
inlineprivate |
Processes detected AprilTags, calculates pose, and publishes overlay image.
input_image | Input image message. |
tag_7_detected_ | Flag for tag 7 detection. |
tag_11_detected_ | Flag for tag 11 detection |
overlay_publisher | Publisher for overlay image. |
calculate_tag_ | Flag to determine whether to calculate yaw and distances for the detected tag. |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |