moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
planning_response.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2012, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34
35/* Author: Ioan Sucan */
36
39
40void planning_interface::MotionPlanResponse::getMessage(moveit_msgs::msg::MotionPlanResponse& msg) const
41{
42 msg.error_code = error_code;
43 msg.planning_time = planning_time;
44 if (trajectory && !trajectory->empty())
45 {
46 moveit::core::robotStateToRobotStateMsg(trajectory->getFirstWayPoint(), msg.trajectory_start);
47 trajectory->getRobotTrajectoryMsg(msg.trajectory);
48 msg.group_name = trajectory->getGroupName();
49 }
50}
51
52void planning_interface::MotionPlanDetailedResponse::getMessage(moveit_msgs::msg::MotionPlanDetailedResponse& msg) const
53{
54 msg.error_code = error_code;
55
56 msg.trajectory.clear();
57 msg.description.clear();
58 msg.processing_time.clear();
59
60 bool first = true;
61
62 for (std::size_t i = 0; i < trajectory.size(); ++i)
63 {
64 if (trajectory[i]->empty())
65 continue;
66 if (first)
67 {
68 first = false;
69 moveit::core::robotStateToRobotStateMsg(trajectory[i]->getFirstWayPoint(), msg.trajectory_start);
70 msg.group_name = trajectory[i]->getGroupName();
71 }
72 msg.trajectory.resize(msg.trajectory.size() + 1);
73 trajectory[i]->getRobotTrajectoryMsg(msg.trajectory.back());
74 if (description.size() > i)
75 msg.description.push_back(description[i]);
76 if (processing_time.size() > i)
77 msg.processing_time.push_back(processing_time[i]);
78 }
79}
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::msg::RobotState &robot_state, bool copy_attached_bodies=true)
Convert a MoveIt robot state to a robot state message.
void getMessage(moveit_msgs::msg::MotionPlanDetailedResponse &msg) const
moveit::core::MoveItErrorCode error_code
robot_trajectory::RobotTrajectoryPtr trajectory
void getMessage(moveit_msgs::msg::MotionPlanResponse &msg) const
Construct a ROS message from struct data.