moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
constrained_planning_state_space.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2020, KU Leuven
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 KU Leuven 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: Jeroen De Maeyer */
36
38
39#include <ompl/base/spaces/constraint/ConstrainedStateSpace.h>
40
41namespace ompl_interface
42{
43const std::string ConstrainedPlanningStateSpace::PARAMETERIZATION_TYPE = "ConstrainedPlanningJointModel";
44
50
51double* ConstrainedPlanningStateSpace::getValueAddressAtIndex(ompl::base::State* ompl_state,
52 const unsigned int index) const
53{
54 assert(ompl_state != nullptr);
55 if (index >= variable_count_)
56 {
57 return nullptr;
58 }
59
60 // Developer tip: replace this with a dynamic_cast for debugging
61 return ompl_state->as<ompl_interface::ConstrainedPlanningStateSpace::StateType>()->values + index;
62}
63
65 const ompl::base::State* ompl_state) const
66{
67 assert(ompl_state != nullptr);
68 robot_state.setJointGroupPositions(
70 ompl_state->as<ompl::base::ConstrainedStateSpace::StateType>()->getState()->as<StateType>()->values);
71 robot_state.update();
72}
73
74void ConstrainedPlanningStateSpace::copyToOMPLState(ompl::base::State* ompl_state,
75 const moveit::core::RobotState& robot_state) const
76{
77 assert(ompl_state != nullptr);
78 robot_state.copyJointGroupPositions(
80 ompl_state->as<ompl::base::ConstrainedStateSpace::StateType>()->getState()->as<StateType>()->values);
81
82 // clear any cached info (such as validity known or not)
83 ompl_state->as<ompl::base::ConstrainedStateSpace::StateType>()->getState()->as<StateType>()->clearKnownInformation();
84}
85
86void ConstrainedPlanningStateSpace::copyJointToOMPLState(ompl::base::State* ompl_state,
87 const moveit::core::RobotState& robot_state,
88 const moveit::core::JointModel* joint_model,
89 int ompl_state_joint_index) const
90{
91 assert(ompl_state != nullptr);
92 assert(joint_model != nullptr);
93 memcpy(getValueAddressAtIndex(ompl_state->as<ompl::base::ConstrainedStateSpace::StateType>()->getState(),
94 ompl_state_joint_index),
95 robot_state.getVariablePositions() + joint_model->getFirstVariableIndex(),
96 joint_model->getVariableCount() * sizeof(double));
97
98 // clear any cached info (such as validity known or not)
99 ompl_state->as<ompl::base::ConstrainedStateSpace::StateType>()->getState()->as<StateType>()->clearKnownInformation();
100}
101} // namespace ompl_interface
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
size_t getFirstVariableIndex() const
Get the index of this joint's first variable within the full robot state.
std::size_t getVariableCount() const
Get the number of variables that describe this joint.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition robot_state.h:90
void setJointGroupPositions(const std::string &joint_group_name, const double *gstate)
Given positions for the variables that make up a group, in the order found in the group (including va...
void copyJointGroupPositions(const std::string &joint_group_name, std::vector< double > &gstate) const
For a given group, copy the position values of the variables that make up the group into another loca...
double * getVariablePositions()
Get a raw pointer to the positions of the variables stored in this state. Use carefully....
void update(bool force=false)
Update all transforms.
void copyJointToOMPLState(ompl::base::State *ompl_state, const moveit::core::RobotState &robot_state, const moveit::core::JointModel *joint_model, int ompl_state_joint_index) const override
Copy a single joint's values (which might have multiple variables) from a MoveIt robot_state to an OM...
double * getValueAddressAtIndex(ompl::base::State *ompl_state, const unsigned int index) const override
void copyToOMPLState(ompl::base::State *ompl_state, const moveit::core::RobotState &robot_state) const override
Copy the data from a set of joint states to an OMPL state.
ConstrainedPlanningStateSpace(const ModelBasedStateSpaceSpecification &spec)
void copyToRobotState(moveit::core::RobotState &robot_state, const ompl::base::State *ompl_state) const override
Copy the data from an OMPL state to a set of joint states.
ModelBasedStateSpaceSpecification spec_
The MoveIt interface to OMPL.
const moveit::core::JointModelGroup * joint_model_group_
bool getState(const std::shared_ptr< moveit_msgs::srv::GetRobotStateFromWarehouse::Request > &request, const std::shared_ptr< moveit_msgs::srv::GetRobotStateFromWarehouse::Response > &response, moveit_warehouse::RobotStateStorage &rs)