Skip to content

Commit

Permalink
Port sensor_manager of moveit_core to ROS 2.0 (#11)
Browse files Browse the repository at this point in the history
  • Loading branch information
Víctor Mayoral Vilches authored and davetcoleman committed Feb 20, 2019
1 parent 9f20d5f commit 5c0a336
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 5 deletions.
2 changes: 1 addition & 1 deletion moveit_core/sensor_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 @@ -40,8 +40,8 @@
#include <vector>
#include <string>
#include <moveit/macros/class_forward.h>
#include <moveit_msgs/RobotTrajectory.h>
#include <geometry_msgs/PointStamped.h>
#include <moveit_msgs/msg/robot_trajectory.hpp>
#include <geometry_msgs/msg/point_stamped.hpp>

/// Namespace for the base class of a MoveIt! sensor manager
namespace moveit_sensor_manager
Expand Down Expand Up @@ -99,8 +99,8 @@ class MoveItSensorManager
/// of this function can perform checks on the safety of the trajectory.
/// The function returns true on success (either completing execution succesfully or computing a trajecotory
/// successufully)
virtual bool pointSensorTo(const std::string& name, const geometry_msgs::PointStamped& target,
moveit_msgs::RobotTrajectory& sensor_trajectory) = 0;
virtual bool pointSensorTo(const std::string& name, const geometry_msgs::msg::PointStamped& target,
moveit_msgs::msg::RobotTrajectory& sensor_trajectory) = 0;
};
}

Expand Down

0 comments on commit 5c0a336

Please sign in to comment.