College of DuPage Lunabotics Documentation
2025
|
Performs excavation sequence after receiving request from the navigation client. More...
Public Types | |
using | Excavation = lunabot_msgs::action::Excavation |
using | GoalHandleExcavation = rclcpp_action::ServerGoalHandle< Excavation > |
Public Member Functions | |
ExcavationServer () | |
Constructor for the ExcavationServer class. More... | |
Private Member Functions | |
rclcpp_action::GoalResponse | handle_goal (const rclcpp_action::GoalUUID &, std::shared_ptr< const Excavation::Goal >) |
Handles goal requests from clients. More... | |
rclcpp_action::CancelResponse | handle_cancel (const std::shared_ptr< GoalHandleExcavation >) |
Handles cancellation requests from clients. More... | |
void | handle_accepted (const std::shared_ptr< GoalHandleExcavation > goal_handle) |
Accepts and starts the goal execution. More... | |
void | execute (const std::shared_ptr< GoalHandleExcavation > goal_handle) |
Executes the Excavation process. More... | |
void | odometry_callback (const nav_msgs::msg::Odometry::SharedPtr msg) |
Callback for the odometry message. More... | |
void | excavate () |
Uses current odometry and compares to goal to navigate the robot to the construction zone. More... | |
double | normalize_angle (double angle) |
Normalizes an angle to the range [-pi, pi]. More... | |
Private Attributes | |
rclcpp_action::Server< Excavation >::SharedPtr | action_server_ |
rclcpp::Publisher< geometry_msgs::msg::Twist >::SharedPtr | cmd_vel_publisher_ |
rclcpp::Subscription< nav_msgs::msg::Odometry >::SharedPtr | odometry_subscriber_ |
rclcpp::TimerBase::SharedPtr | odometry_timer_ |
rclcpp::TimerBase::SharedPtr | excavation_timer_ |
rclcpp::Time | previous_time_ |
bool | success_ |
bool | goal_active_ |
bool | alignment_done_ |
double | current_x_ |
double | current_y_ |
double | current_roll_ |
double | current_pitch_ |
double | current_yaw_ |
double | previous_error_ |
double | error_sum_ |
Performs excavation sequence after receiving request from the navigation client.
using ExcavationServer::Excavation = lunabot_msgs::action::Excavation |
using ExcavationServer::GoalHandleExcavation = rclcpp_action::ServerGoalHandle<Excavation> |
|
inline |
Constructor for the ExcavationServer class.
|
inlineprivate |
Uses current odometry and compares to goal to navigate the robot to the construction zone.
|
inlineprivate |
Executes the Excavation 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 |
Normalizes an angle to the range [-pi, pi].
angle | The angle to normalize. |
|
inlineprivate |
Callback for the odometry message.
msg | The odometry message. |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |