moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
robot_poses.hpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2021, PickNik Robotics
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 Robotics 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: David V. Lu!! */
36#pragma once
37
39#include <moveit_msgs/msg/display_robot_state.hpp>
40
41namespace moveit_setup
42{
43namespace srdf_setup
44{
45// Note: Does not derive from SuperSRDFStep because we always need to check the name AND the group name for each pose
46class RobotPoses : public SRDFStep
47{
48public:
49 std::string getName() const override
50 {
51 return "Robot Poses";
52 }
53
54 void onInit() override;
55
56 bool isReady() const override
57 {
58 return hasGroups();
59 }
60
61 std::vector<std::string> getGroupNames() const
62 {
63 return srdf_config_->getGroupNames();
64 }
65
72 srdf::Model::GroupState* findPoseByName(const std::string& name, const std::string& group);
73
74 std::vector<srdf::Model::GroupState>& getGroupStates()
75 {
76 return srdf_config_->getGroupStates();
77 }
78
80 {
81 return srdf_config_->getPlanningScene()->getCurrentStateNonConst();
82 }
83
87 void publishState(const moveit::core::RobotState& robot_state);
88
92 bool checkSelfCollision(const moveit::core::RobotState& robot_state);
93
100 std::vector<const moveit::core::JointModel*> getSimpleJointModels(const std::string& group_name) const;
101
102 void removePoseByName(const std::string& pose_name, const std::string& group_name)
103 {
104 srdf_config_->removePoseByName(pose_name, group_name);
105 }
106
107 void setToCurrentValues(srdf::Model::GroupState& group_state);
108
111
112protected:
114 rclcpp::Publisher<moveit_msgs::msg::DisplayRobotState>::SharedPtr pub_robot_state_;
115
116 // ******************************************************************************************
117 // Collision Variables
118 // ******************************************************************************************
120
123};
124} // namespace srdf_setup
125} // namespace moveit_setup
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition robot_state.h:90
void setToCurrentValues(srdf::Model::GroupState &group_state)
moveit::core::RobotState & getState()
void loadAllowedCollisionMatrix()
Load the allowed collision matrix from the SRDF's list of link pairs.
std::vector< std::string > getGroupNames() const
std::vector< const moveit::core::JointModel * > getSimpleJointModels(const std::string &group_name) const
Returns a vector of joint models for the given group name.
void onInit() override
Overridable initialization method.
void publishState(const moveit::core::RobotState &robot_state)
Publish the given state on the moveit_robot_state topic.
collision_detection::AllowedCollisionMatrix allowed_collision_matrix_
Allowed collision matrix for robot poses.
srdf::Model::GroupState * findPoseByName(const std::string &name, const std::string &group)
collision_detection::CollisionRequest request_
bool isReady() const override
Return true if the data necessary to proceed with this step has been configured.
rclcpp::Publisher< moveit_msgs::msg::DisplayRobotState >::SharedPtr pub_robot_state_
Remember the publisher for quick publishing later.
bool checkSelfCollision(const moveit::core::RobotState &robot_state)
Check if the given robot state is in collision.
std::string getName() const override
Returns the name of the setup step.
std::vector< srdf::Model::GroupState > & getGroupStates()
void removePoseByName(const std::string &pose_name, const std::string &group_name)
Setup Step that contains the SRDFConfig.
Definition srdf_step.hpp:49
std::shared_ptr< SRDFConfig > srdf_config_
Definition srdf_step.hpp:67
Representation of a collision checking request.