Execute Mission
Send the platform on an autonomous mission to various locations around the map.
-
Action Name: autonomy/mission
-
Action Type: clearpath_navigation_msgs/action/ExecuteMission
- Python
- C++
from action_msgs.msg import GoalStatus # Import for reference to status constants
from clearpath_config.common.utils.yaml import read_yaml
from clearpath_navigation_msgs.action import ExecuteMission
import rclpy
from rclpy.action import ActionClient
from rclpy.node import Node
ROBOT_CONFIG_PATH = '/etc/clearpath/robot.yaml'
LOGGING_NAME = 'ExecuteMission'
# TODO: Enter your mission and map uuids
MISSION_ID: str = ''
MAP_ID: str = ''
class ExecuteMissionActionClient(Node):
def __init__(self, namespace: str):
super().__init__('execute_mission')
self._namespace = namespace
self._action_client = ActionClient(self, ExecuteMission, f'/{self._namespace}/autonomy/mission')
self._mission_goal_handle = None
self._mission_goal_cancelled = False
self._mission_running = False
self._mission_completed = False
###################################
# Mission Action Client Functions #
###################################
def send_mission_goal(self, mission_id, map_id):
# populate goal message
goal_msg = ExecuteMission.Goal()
goal_msg.mission_uuid = mission_id
goal_msg.map_uuid = map_id
if not self._action_client.wait_for_server(timeout_sec=5.0):
self.get_logger().error(f'[{LOGGING_NAME}] /{self._namespace}/autonomy/mission action server not available!')
self.destroy_node()
rclpy.shutdown()
return
self._send_goal_future = self._action_client.send_goal_async(goal_msg, feedback_callback=self.mission_feedback_cb)
self._send_goal_future.add_done_callback(self.mission_goal_response_cb)
def mission_goal_response_cb(self, future):
self._mission_goal_handle = future.result()
if not self._mission_goal_handle.accepted:
self.get_logger().info(f'[{LOGGING_NAME}] Mission Goal rejected')
self._mission_goal_handle = None
self.destroy_node()
rclpy.shutdown()
return
self._mission_running = True
self._mission_completed = False
self._mission_goal_cancelled = False
self.get_logger().info(f'[{LOGGING_NAME}] Mission Goal accepted')
self._get_result_future = self._mission_goal_handle.get_result_async()
self._get_result_future.add_done_callback(self.mission_get_result_cb)
def mission_feedback_cb(self, feedback_msg):
feedback = feedback_msg.feedback
self.get_logger().info(f'[{LOGGING_NAME}] Mission has been running for: {feedback.elapsed_time:.2f}s', throttle_duration_sec=60)
def mission_cancel_response_cb(self, future):
cancel_response = future.result()
self.get_logger().info(f'[{LOGGING_NAME}] Cancel response received: {cancel_response.return_code}')
if len(cancel_response.goals_canceling) > 0:
self.get_logger().info(f'[{LOGGING_NAME}] Canceling of mission goal complete')
else:
self.get_logger().warning(f'[{LOGGING_NAME}] Mission Goal failed to cancel')
def mission_get_result_cb(self, future):
result = future.result().result
status = future.result().status
# Compare the status integer against the constants defined in the message
if status == GoalStatus.STATUS_SUCCEEDED:
if result.success:
self.get_logger().info(f'[{LOGGING_NAME}] [Mission Goal Result] Succeeded! Result: Robot completed mission!')
self._mission_completed = True
else:
self.get_logger().info(f'[{LOGGING_NAME}] [Mission Goal Result] Succeeded! Result: Robot failed to complete mission')
elif status == GoalStatus.STATUS_CANCELED:
self.get_logger().info(f'[{LOGGING_NAME}] [Mission Goal Result] Cancelled!')
self._mission_goal_cancelled = True
elif status == GoalStatus.STATUS_ABORTED:
self.get_logger().info(f'[{LOGGING_NAME}] [Mission Goal Result] Aborted!')
else:
self.get_logger().info(f'[{LOGGING_NAME}] [Mission Goal Result] Finished with unknown status: {status}')
self._mission_goal_handle = None
self._mission_running = False
self.destroy_node()
rclpy.shutdown()
def main(args=None):
rclpy.init(args=args)
robot_config = read_yaml(ROBOT_CONFIG_PATH)
namespace = robot_config['system']['ros2']['namespace']
mission = ExecuteMissionActionClient(namespace)
mission.send_mission_goal(MISSION_ID, MAP_ID)
rclpy.spin(mission)
if __name__ == '__main__':
main()
#include <functional>
#include <future>
#include <memory>
#include <string>
#include <yaml-cpp/yaml.h>
#include "clearpath_navigation_msgs/action/execute_mission.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_action/rclcpp_action.hpp"
#include "rclcpp_components/register_node_macro.hpp"
// TODO: Enter your mission and map uuids
const std::string MISSION_ID = "";
const std::string MAP_ID = "";
namespace mission_action_client
{
class ExecuteMissionActionClient : public rclcpp::Node
{
public:
using ExecuteMission = clearpath_navigation_msgs::action::ExecuteMission;
using GoalHandleExecuteMission = rclcpp_action::ClientGoalHandle<ExecuteMission>;
explicit ExecuteMissionActionClient(const rclcpp::NodeOptions & options)
: Node("execute_mission", options)
{
YAML::Node robot_config = YAML::LoadFile("/etc/clearpath/robot.yaml");
namespace_ = robot_config["system"]["ros2"]["namespace"].as<std::string>();
this->client_ptr_ = rclcpp_action::create_client<ExecuteMission>(
this, "/" + namespace_ + "/" + std::string("autonomy/mission"));
this->timer_ = this->create_wall_timer(
std::chrono::milliseconds(500),
std::bind(&ExecuteMissionActionClient::send_goal, this));
}
void send_goal()
{
using namespace std::placeholders;
this->timer_->cancel();
if (!this->client_ptr_->wait_for_action_server()) {
RCLCPP_ERROR(this->get_logger(), "%s/autonomy/mission Action server not available after waiting", namespace_.c_str());
rclcpp::shutdown();
}
auto goal_msg = ExecuteMission::Goal();
goal_msg.mission_uuid = MISSION_ID;
goal_msg.map_uuid = MAP_ID;
auto send_goal_options = rclcpp_action::Client<ExecuteMission>::SendGoalOptions();
send_goal_options.goal_response_callback = [this](const GoalHandleExecuteMission::SharedPtr & goal_handle)
{
if (!goal_handle) {
RCLCPP_ERROR(this->get_logger(), "Mission Goal was rejected by server");
} else {
RCLCPP_INFO(this->get_logger(), "Mission Goal accepted by server, waiting for result");
}
};
send_goal_options.feedback_callback = [this](
GoalHandleExecuteMission::SharedPtr,
const std::shared_ptr<const ExecuteMission::Feedback> feedback)
{
RCLCPP_INFO_THROTTLE(this->get_logger(), *this->get_clock(), 60000, "Mission has been running for: %.3f", feedback->elapsed_time);
};
send_goal_options.result_callback = [this](const GoalHandleExecuteMission::WrappedResult & result)
{
switch (result.code) {
case rclcpp_action::ResultCode::SUCCEEDED:
if (result.result->success)
{
RCLCPP_INFO(this->get_logger(), "[Mission Goal Result] Succeeded! Result: Robot completed mission!");
}
else
{
RCLCPP_ERROR(this->get_logger(), "[Mission Goal Result] Succeeded! Result: Robot failed to complete mission");
}
break;
case rclcpp_action::ResultCode::ABORTED:
RCLCPP_ERROR(this->get_logger(), "[Mission Goal Result] Aborted!");
return;
case rclcpp_action::ResultCode::CANCELED:
RCLCPP_ERROR(this->get_logger(), "[Mission Goal Result] Cancelled!");
return;
default:
RCLCPP_ERROR(this->get_logger(), "[Mission Goal Result] Finished with unknown code");
return;
}
rclcpp::shutdown();
};
this->client_ptr_->async_send_goal(goal_msg, send_goal_options);
}
private:
rclcpp_action::Client<ExecuteMission>::SharedPtr client_ptr_;
rclcpp::TimerBase::SharedPtr timer_;
std::string namespace_;
}; // class ExecuteMissionActionClient
} // namespace mission_action_client
int main()
{
}
RCLCPP_COMPONENTS_REGISTER_NODE(mission_action_client::ExecuteMissionActionClient)