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

Port controller_manager submodule of moveit_core to ROS 2 #6

Merged
merged 2 commits into from
Feb 25, 2019
Merged
Show file tree
Hide file tree
Changes from all commits
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
2 changes: 1 addition & 1 deletion moveit_core/controller_manager/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1 +1 @@
install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION})
install(DIRECTORY include/ DESTINATION include)
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@

#include <vector>
#include <string>
#include <moveit_msgs/RobotTrajectory.h>
#include <moveit_msgs/msg/robot_trajectory.hpp>
#include <moveit/macros/class_forward.h>

/// Namespace for the base class of a MoveIt! controller manager
Expand Down Expand Up @@ -121,11 +121,11 @@ class MoveItControllerHandle
}

/** \brief Send a trajectory to the controller.
*
* 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. */
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

regression in commenting

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@anasarrak can you please review this?

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

virtual bool sendTrajectory(const moveit_msgs::RobotTrajectory& trajectory) = 0;
*
* 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 Down