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

Planning interface, port to ROS 2 #61

Merged
merged 2 commits into from
Apr 8, 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
17 changes: 10 additions & 7 deletions moveit_core/planning_interface/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -5,12 +5,15 @@ add_library(${MOVEIT_LIB_NAME}
src/planning_response.cpp
)
set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}")

target_link_libraries(${MOVEIT_LIB_NAME} moveit_robot_state moveit_robot_trajectory ${catkin_LIBRARIES} ${urdfdom_LIBRARIES} ${urdfdom_headers_LIBRARIES} ${Boost_LIBRARIES})
add_dependencies(${MOVEIT_LIB_NAME} ${catkin_EXPORTED_TARGETS})
ament_target_dependencies(${MOVEIT_LIB_NAME}
urdf
visualization_msgs
moveit_robot_state
moveit_robot_trajectory
urdfdom
urdfdom_headers)

install(TARGETS ${MOVEIT_LIB_NAME}
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION})

install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION})
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib)
install(DIRECTORY include/ DESTINATION include)
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,7 @@
#include <moveit/planning_interface/planning_response.h>
#include <string>
#include <map>
#include "rclcpp/rclcpp.hpp"

namespace planning_scene
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@
#ifndef MOVEIT_PLANNING_INTERFACE_PLANNING_REQUEST_
#define MOVEIT_PLANNING_INTERFACE_PLANNING_REQUEST_

#include <moveit_msgs/MotionPlanRequest.h>
#include <moveit_msgs/msg/motion_plan_request.hpp>

namespace planning_interface
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,9 +38,9 @@
#define MOVEIT_PLANNING_INTERFACE_PLANNING_RESPONSE_

#include <moveit/robot_trajectory/robot_trajectory.h>
#include <moveit_msgs/MoveItErrorCodes.h>
#include <moveit_msgs/MotionPlanResponse.h>
#include <moveit_msgs/MotionPlanDetailedResponse.h>
#include <moveit_msgs/msg/move_it_error_codes.hpp>
#include <moveit_msgs/msg/motion_plan_response.hpp>
#include <moveit_msgs/msg/motion_plan_detailed_response.hpp>

namespace planning_interface
{
Expand Down
8 changes: 5 additions & 3 deletions moveit_core/planning_interface/src/planning_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,8 @@

namespace planning_interface
{
rclcpp::Logger LOGGER = rclcpp::get_logger("moveit").get_child("planning_interface");

namespace
{
// keep track of currently active contexts
Expand Down Expand Up @@ -80,13 +82,13 @@ void PlanningContext::setMotionPlanRequest(const MotionPlanRequest& request)
request_ = request;
if (request_.allowed_planning_time <= 0.0)
{
ROS_INFO_NAMED("planning_interface",
RCLCPP_INFO(LOGGER,
"The timeout for planning must be positive (%lf specified). Assuming one second instead.",
request_.allowed_planning_time);
request_.allowed_planning_time = 1.0;
}
if (request_.num_planning_attempts < 0)
ROS_ERROR_NAMED("planning_interface", "The number of desired planning attempts should be positive. "
RCLCPP_ERROR(LOGGER, "The number of desired planning attempts should be positive. "
"Assuming one attempt.");
Copy link
Contributor

Choose a reason for hiding this comment

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

clang format will fix this for you

request_.num_planning_attempts = std::max(1, request_.num_planning_attempts);
}
Expand Down Expand Up @@ -127,4 +129,4 @@ void PlannerManager::terminate() const
(*it)->terminate();
}

} // end of namespace planning_interface
} // end of namespace planning_interface