Skip to content

Commit

Permalink
[moveit_cpp] Return ExecutionStatus in execute
Browse files Browse the repository at this point in the history
Return an `ExecutionStatus` in `MoveItCpp::execute`, which can is
convertible to a bool in the caller code.
This change introduces a forward-compatible API breaking change.

Signed-off-by: Gaël Écorchard <gael.ecorchard@cvut.cz>
  • Loading branch information
galou committed Mar 29, 2022
1 parent a772d8e commit e61d45d
Show file tree
Hide file tree
Showing 2 changed files with 12 additions and 7 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@
#pragma once

#include <rclcpp/rclcpp.hpp>
#include <moveit/controller_manager/controller_manager.h>
#include <moveit/planning_scene_monitor/planning_scene_monitor.h>
#include <moveit/planning_pipeline/planning_pipeline.h>
#include <moveit/trajectory_execution_manager/trajectory_execution_manager.h>
Expand Down Expand Up @@ -167,8 +168,9 @@ class MoveItCpp

/** \brief Execute a trajectory on the planning group specified by group_name using the trajectory execution manager.
* If blocking is set to false, the execution is run in background and the function returns immediately. */
bool execute(const std::string& group_name, const robot_trajectory::RobotTrajectoryPtr& robot_trajectory,
bool blocking = true);
moveit_controller_manager::ExecutionStatus execute(const std::string& group_name,
const robot_trajectory::RobotTrajectoryPtr& robot_trajectory,
bool blocking = true);

private:
// Core properties and instances
Expand Down
13 changes: 8 additions & 5 deletions moveit_ros/planning/moveit_cpp/src/moveit_cpp.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,8 @@
/* Author: Henning Kayser */

#include <stdexcept>

#include <moveit/controller_manager/controller_manager.h>
#include <moveit/moveit_cpp/moveit_cpp.h>
#if __has_include(<tf2_geometry_msgs/tf2_geometry_msgs.hpp>)
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
Expand Down Expand Up @@ -247,20 +249,21 @@ trajectory_execution_manager::TrajectoryExecutionManagerPtr MoveItCpp::getTrajec
return trajectory_execution_manager_;
}

bool MoveItCpp::execute(const std::string& group_name, const robot_trajectory::RobotTrajectoryPtr& robot_trajectory,
bool blocking)
moveit_controller_manager::ExecutionStatus
MoveItCpp::execute(const std::string& group_name, const robot_trajectory::RobotTrajectoryPtr& robot_trajectory,
bool blocking)
{
if (!robot_trajectory)
{
RCLCPP_ERROR(LOGGER, "Robot trajectory is undefined");
return false;
return moveit_controller_manager::ExecutionStatus::ABORTED;
}

// Check if there are controllers that can handle the execution
if (!trajectory_execution_manager_->ensureActiveControllersForGroup(group_name))
{
RCLCPP_ERROR(LOGGER, "Execution failed! No active controllers configured for group '%s'", group_name.c_str());
return false;
return moveit_controller_manager::ExecutionStatus::ABORTED;
}

// Execute trajectory
Expand All @@ -273,7 +276,7 @@ bool MoveItCpp::execute(const std::string& group_name, const robot_trajectory::R
return trajectory_execution_manager_->waitForExecution();
}
trajectory_execution_manager_->pushAndExecute(robot_trajectory_msg);
return true;
return moveit_controller_manager::ExecutionStatus::RUNNING;
}

const std::shared_ptr<tf2_ros::Buffer>& MoveItCpp::getTFBuffer() const
Expand Down

0 comments on commit e61d45d

Please sign in to comment.