This repository has been archived by the owner on May 11, 2023. It is now read-only.
-
Notifications
You must be signed in to change notification settings - Fork 3
/
Copy pathstomp_moveit_planner_plugin.cpp
104 lines (82 loc) · 3.07 KB
/
stomp_moveit_planner_plugin.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
#include <class_loader/class_loader.hpp>
#include <stomp_moveit/stomp_moveit_planning_context.hpp>
#include <rclcpp/node.hpp>
#include <rclcpp/logging.hpp>
#include <visualization_msgs/msg/marker_array.hpp>
namespace stomp_moveit
{
static const rclcpp::Logger LOGGER = rclcpp::get_logger("stomp_moveit");
using namespace planning_interface;
class StompPlannerManager : public PlannerManager
{
public:
StompPlannerManager() = default;
~StompPlannerManager() override = default;
bool initialize(const moveit::core::RobotModelConstPtr& model, const rclcpp::Node::SharedPtr& node,
const std::string& parameter_namespace) override
{
robot_model_ = model;
node_ = node;
parameter_namespace_ = parameter_namespace;
param_listener_ = std::make_shared<stomp_moveit::ParamListener>(node, parameter_namespace);
return true;
}
std::string getDescription() const override
{
return "STOMP";
}
void getPlanningAlgorithms(std::vector<std::string>& algs) const override
{
algs = { "STOMP" };
}
PlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr& planning_scene,
const MotionPlanRequest& req,
moveit_msgs::msg::MoveItErrorCodes& error_code) const override
{
if (!canServiceRequest(req))
{
error_code.val = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
return nullptr;
}
auto const params = param_listener_->get_params();
std::shared_ptr<StompPlanningContext> planning_context =
std::make_shared<StompPlanningContext>("STOMP", req.group_name, params);
planning_context->setPlanningScene(planning_scene);
planning_context->setMotionPlanRequest(req);
if (!params.path_marker_topic.empty())
{
auto path_publisher = node_->create_publisher<visualization_msgs::msg::MarkerArray>(params.path_marker_topic,
rclcpp::SystemDefaultsQoS());
planning_context->setPathPublisher(path_publisher);
}
return planning_context;
}
bool canServiceRequest(const MotionPlanRequest& req) const override
{
if (req.goal_constraints.empty())
{
RCLCPP_ERROR(LOGGER, "Invalid goal constraints");
return false;
}
if (req.group_name.empty() || !robot_model_->hasJointModelGroup(req.group_name))
{
RCLCPP_ERROR(LOGGER, "Invalid joint group '%s'", req.group_name.c_str());
return false;
}
if (!req.reference_trajectories.empty())
{
RCLCPP_WARN(LOGGER, "Ignoring reference trajectories - not implemented!");
}
return true;
}
void setPlannerConfigurations(const PlannerConfigurationMap& /*pcs*/) override
{
}
private:
moveit::core::RobotModelConstPtr robot_model_;
rclcpp::Node::SharedPtr node_;
std::string parameter_namespace_;
std::shared_ptr<stomp_moveit::ParamListener> param_listener_;
};
} // namespace stomp_moveit
CLASS_LOADER_REGISTER_CLASS(stomp_moveit::StompPlannerManager, planning_interface::PlannerManager)