Skip to content

Commit

Permalink
Controller manager port to ROS 2 (#84)
Browse files Browse the repository at this point in the history
* include rclcpp to controler_manager and update the duration
* controller_manager - adding initialize including the node
  • Loading branch information
ahcorde authored and mlautman committed May 21, 2019
1 parent 200d41b commit ea14cb5
Showing 1 changed file with 4 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@
#include <string>
#include <moveit_msgs/msg/robot_trajectory.hpp>
#include <moveit/macros/class_forward.h>
#include "rclcpp/rclcpp.hpp"

/// Namespace for the base class of a MoveIt! controller manager
namespace moveit_controller_manager
Expand Down Expand Up @@ -125,10 +126,6 @@ class MoveItControllerHandle
* The controller is expected to execute the trajectory, but this function call should not block.
* Blocking is achievable by calling waitForExecution().
* Return false when the controller cannot accept the trajectory. */
*
* The controller is expected to execute the trajectory, but this function call should not block.
* Blocking is achievable by calling waitForExecution().
* Return false when the controller cannot accept the trajectory. */
virtual bool sendTrajectory(const moveit_msgs::msg::RobotTrajectory& trajectory) = 0;

/** \brief Cancel the execution of any motion using this controller.
Expand All @@ -142,7 +139,7 @@ class MoveItControllerHandle
* Return true if the execution is complete (whether successful or not).
* Return false if timeout was reached.
* If timeout is 0 (default argument), wait until the execution is complete (no timeout). */
virtual bool waitForExecution(const ros::Duration& timeout = ros::Duration(0)) = 0;
virtual bool waitForExecution(const rclcpp::Duration& timeout = rclcpp::Duration(0.0)) = 0;

/** \brief Return the execution status of the last trajectory sent to the controller. */
virtual ExecutionStatus getLastExecutionStatus() = 0;
Expand Down Expand Up @@ -187,6 +184,8 @@ class MoveItControllerManager
{
}

virtual void initialize(std::shared_ptr<rclcpp::Node>& node) = 0;

/** \brief Return a given named controller. */
virtual MoveItControllerHandlePtr getControllerHandle(const std::string& name) = 0;

Expand Down

0 comments on commit ea14cb5

Please sign in to comment.