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

Improvements in Planning interface port to ROS 2 #86

Merged
merged 5 commits into from
Jun 1, 2019
Merged
Show file tree
Hide file tree
Changes from 3 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
6 changes: 5 additions & 1 deletion moveit_core/planning_interface/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
set(MOVEIT_LIB_NAME moveit_planning_interface)

add_library(${MOVEIT_LIB_NAME}
add_library(${MOVEIT_LIB_NAME} SHARED
src/planning_interface.cpp
src/planning_response.cpp
)
Expand All @@ -13,6 +13,10 @@ ament_target_dependencies(${MOVEIT_LIB_NAME}
urdfdom
urdfdom_headers)

target_link_libraries(${MOVEIT_LIB_NAME}
moveit_robot_trajectory
moveit_robot_state)

install(TARGETS ${MOVEIT_LIB_NAME}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -165,7 +165,7 @@ class PlannerManager
/// It is assumed that motion plans will be computed for the robot described by \e model and that any exposed ROS
/// functionality
/// or required ROS parameters are namespaced by \e ns
ahcorde marked this conversation as resolved.
Show resolved Hide resolved
virtual bool initialize(const robot_model::RobotModelConstPtr& model, const std::string& ns);
virtual bool initialize(const robot_model::RobotModelConstPtr& model, std::shared_ptr<rclcpp::Node>& node);

/// Get \brief a short string that identifies the planning interface
virtual std::string getDescription() const;
Expand Down
2 changes: 1 addition & 1 deletion moveit_core/planning_interface/src/planning_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -93,7 +93,7 @@ void PlanningContext::setMotionPlanRequest(const MotionPlanRequest& request)
request_.num_planning_attempts = std::max(1, request_.num_planning_attempts);
}

bool PlannerManager::initialize(const robot_model::RobotModelConstPtr& /*unused*/, const std::string& /*unused*/)
bool PlannerManager::initialize(const robot_model::RobotModelConstPtr& /*unused*/, std::shared_ptr<rclcpp::Node>& node)
{
return true;
}
Expand Down