Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[moveit_cpp] Return ExecutionStatus in execute #1147

Merged
merged 3 commits into from
Mar 29, 2022
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions MIGRATION.md
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@ API changes in MoveIt releases
- add API for passing RNG to setToRandomPositionsNearBy
- Static member variable interface of the CollisionDetectorAllocatorTemplate for the string NAME was replaced with a virtual method `getName`.
- Enhance `RDFLoader` to load from string parameter OR string topic (and add the ability to publish a string topic).
- `MoveItCpp::execute` now returns a `moveit_controller_manager::ExecutionStatus` rather than a `bool`. A `moveit_controller_manager::ExecutionStatus` is automatically casted to a `bool`, so that no changes in the user's code should be required.
henningkayser marked this conversation as resolved.
Show resolved Hide resolved

## ROS Noetic
- RobotModel no longer overrides empty URDF collision geometry by matching the visual geometry of the link.
Expand Down
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