moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
load_test_robot.h
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
37#pragma once
41#include <fstream>
42
44{
99{
100protected:
101 LoadTestRobot(const std::string& robot_name, const std::string& group_name)
102 : group_name_(group_name), robot_name_(robot_name)
103 {
104 // load robot
106 robot_state_ = std::make_shared<moveit::core::RobotState>(robot_model_);
107 robot_state_->setToDefaultValues();
108 joint_model_group_ = robot_state_->getJointModelGroup(group_name_);
109
110 // extract useful parameters for tests
113 base_link_name_ = robot_model_->getRootLinkName();
114
115 std::cout << "Loading robot: " << robot_name << " for planning group: " << group_name << '\n';
116 }
117
118 Eigen::VectorXd getRandomState() const
119 {
120 robot_state_->setToRandomPositions(joint_model_group_);
121 Eigen::VectorXd q;
122 robot_state_->copyJointGroupPositions(joint_model_group_, q);
123 return q;
124 }
125
129 Eigen::VectorXd getDeterministicState() const
130 {
131 Eigen::VectorXd state(num_dofs_);
132 double value = 0.1;
133 for (std::size_t i = 0; i < num_dofs_; ++i)
134 {
135 state[i] = value;
136 value += 0.1;
137 }
138 return state;
139 }
140
141protected:
142 std::string group_name_;
143 std::string robot_name_;
144
145 moveit::core::RobotModelPtr robot_model_;
146 moveit::core::RobotStatePtr robot_state_;
148
149 std::size_t num_dofs_;
150 std::string base_link_name_;
151 std::string ee_link_name_;
152};
153} // namespace ompl_interface_testing
unsigned int getVariableCount() const
Get the number of variables that describe this joint group. This includes variables necessary for mim...
const std::vector< std::string > & getLinkModelNames() const
Get the names of the links that are part of this joint group.
Robot independent test class setup.
moveit::core::RobotStatePtr robot_state_
Eigen::VectorXd getDeterministicState() const
Create a joint position vector with values 0.1, 0.2, 0.3, ... where the length depends on the number ...
moveit::core::RobotModelPtr robot_model_
LoadTestRobot(const std::string &robot_name, const std::string &group_name)
const moveit::core::JointModelGroup * joint_model_group_
moveit::core::RobotModelPtr loadTestingRobotModel(const std::string &robot_name)
Loads a robot from moveit_resources.