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
38 
42 
44 {
98 class LoadTestRobot
99 {
100 protected:
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<robot_state::RobotState>(robot_model_);
107  robot_state_->setToDefaultValues();
108  joint_model_group_ = robot_state_->getJointModelGroup(group_name_);
109 
110  // extract useful parameters for tests
111  num_dofs_ = joint_model_group_->getVariableCount();
112  ee_link_name_ = joint_model_group_->getLinkModelNames().back();
113  base_link_name_ = robot_model_->getRootLinkName();
114 
115  ROS_INFO_STREAM("Created test robot named: " << robot_name_ << " for planning group " << group_name_);
116  }
117 
118 protected:
119  const std::string group_name_;
120  const std::string robot_name_;
121 
122  moveit::core::RobotModelPtr robot_model_;
123  robot_state::RobotStatePtr robot_state_;
124  const robot_state::JointModelGroup* joint_model_group_;
125 
126  std::size_t num_dofs_;
127  std::string base_link_name_;
128  std::string ee_link_name_;
129 };
130 } // namespace ompl_interface_testing
robot_model.h
ompl_interface_testing::LoadTestRobot::robot_name_
const std::string robot_name_
Definition: load_test_robot.h:184
ompl_interface_testing::LoadTestRobot::ee_link_name_
std::string ee_link_name_
Definition: load_test_robot.h:192
ompl_interface_testing
Definition: load_test_robot.h:43
robot_state.h
ompl_interface_testing::LoadTestRobot
Robot independent test class setup.
Definition: load_test_robot.h:130
ompl_interface_testing::LoadTestRobot::base_link_name_
std::string base_link_name_
Definition: load_test_robot.h:191
ompl_interface_testing::LoadTestRobot::LoadTestRobot
LoadTestRobot(const std::string &robot_name, const std::string &group_name)
Definition: load_test_robot.h:165
ompl_interface_testing::LoadTestRobot::joint_model_group_
const robot_state::JointModelGroup * joint_model_group_
Definition: load_test_robot.h:188
ompl_interface_testing::LoadTestRobot::group_name_
const std::string group_name_
Definition: load_test_robot.h:183
ompl_interface_testing::LoadTestRobot::num_dofs_
std::size_t num_dofs_
Definition: load_test_robot.h:190
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
ompl_interface_testing::LoadTestRobot::robot_state_
robot_state::RobotStatePtr robot_state_
Definition: load_test_robot.h:187
ompl_interface_testing::LoadTestRobot::robot_model_
moveit::core::RobotModelPtr robot_model_
Definition: load_test_robot.h:186
robot_model_test_utils.h
moveit::core::loadTestingRobotModel
moveit::core::RobotModelPtr loadTestingRobotModel(const std::string &robot_name)


ompl
Author(s): Ioan Sucan
autogenerated on Wed Feb 21 2024 03:26:02