moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
conversion_functions.hpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2023, PickNik 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 PickNik Inc. 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
40#pragma once
41
44
45namespace stomp_moveit
46{
47using Joints = std::vector<const moveit::core::JointModel*>;
48
57std::vector<double> getPositions(const moveit::core::RobotState& state, const Joints& joints)
58{
59 std::vector<double> positions;
60 for (const auto& joint : joints)
61 {
62 positions.push_back(*state.getJointPositions(joint));
63 }
64
65 return positions;
66}
67
77void setJointPositions(const Eigen::VectorXd& values, const Joints& joints, moveit::core::RobotState& state)
78{
79 for (size_t joint_index = 0; joint_index < joints.size(); ++joint_index)
80 {
81 state.setJointPositions(joints[joint_index], &values[joint_index]);
82 }
83}
84
92void fillRobotTrajectory(const Eigen::MatrixXd& trajectory_values, const moveit::core::RobotState& reference_state,
94{
95 trajectory.clear();
96 const auto& active_joints = trajectory.getGroup() ? trajectory.getGroup()->getActiveJointModels() :
97 trajectory.getRobotModel()->getActiveJointModels();
98 assert(static_cast<std::size_t>(trajectory_values.rows()) == active_joints.size());
99
100 for (int timestep = 0; timestep < trajectory_values.cols(); ++timestep)
101 {
102 const auto waypoint = std::make_shared<moveit::core::RobotState>(reference_state);
103 setJointPositions(trajectory_values.col(timestep), active_joints, *waypoint);
104
105 trajectory.addSuffixWayPoint(waypoint, 0.1 /* placeholder dt */);
106 }
107}
108
118robot_trajectory::RobotTrajectory matrixToRobotTrajectory(const Eigen::MatrixXd& trajectory_values,
119 const moveit::core::RobotState& reference_state,
120 const moveit::core::JointModelGroup* group = nullptr)
121{
122 robot_trajectory::RobotTrajectory trajectory(reference_state.getRobotModel(), group);
123 fillRobotTrajectory(trajectory_values, reference_state, trajectory);
124 return trajectory;
125}
126
135{
136 const auto& active_joints = trajectory.getGroup() ? trajectory.getGroup()->getActiveJointModels() :
137 trajectory.getRobotModel()->getActiveJointModels();
138
139 Eigen::MatrixXd trajectory_values(active_joints.size(), trajectory.getWayPointCount());
140
141 for (int timestep = 0; timestep < trajectory_values.cols(); ++timestep)
142 {
143 const auto& waypoint = trajectory.getWayPoint(timestep);
144 for (size_t joint_index = 0; joint_index < active_joints.size(); ++joint_index)
145 {
146 trajectory_values(joint_index, timestep) = *waypoint.getJointPositions(active_joints[joint_index]);
147 }
148 }
149
150 return trajectory_values;
151}
152
153} // namespace stomp_moveit
const std::vector< const JointModel * > & getActiveJointModels() const
Get the active joints in this group (that have controllable DOF). This does not include mimic joints.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition robot_state.h:90
const double * getJointPositions(const std::string &joint_name) const
const RobotModelConstPtr & getRobotModel() const
Get the robot model this state is constructed for.
void setJointPositions(const std::string &joint_name, const double *position)
Maintain a sequence of waypoints and the time durations between these waypoints.
RobotTrajectory & addSuffixWayPoint(const moveit::core::RobotState &state, double dt)
Add a point to the trajectory.
const moveit::core::RobotModelConstPtr & getRobotModel() const
const moveit::core::JointModelGroup * getGroup() const
const moveit::core::RobotState & getWayPoint(std::size_t index) const
Eigen::MatrixXd robotTrajectoryToMatrix(const robot_trajectory::RobotTrajectory &trajectory)
void fillRobotTrajectory(const Eigen::MatrixXd &trajectory_values, const moveit::core::RobotState &reference_state, robot_trajectory::RobotTrajectory &trajectory)
void setJointPositions(const Eigen::VectorXd &values, const Joints &joints, moveit::core::RobotState &state)
std::vector< const moveit::core::JointModel * > Joints
robot_trajectory::RobotTrajectory matrixToRobotTrajectory(const Eigen::MatrixXd &trajectory_values, const moveit::core::RobotState &reference_state, const moveit::core::JointModelGroup *group=nullptr)
std::vector< double > getPositions(const moveit::core::RobotState &state, const Joints &joints)