display_solution.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, Bielefeld University
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 Bielefeld University 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: Robert Haschke */
36 
37 #pragma once
38 
39 #include <moveit_task_constructor_msgs/Solution.h>
41 
42 namespace moveit {
43 namespace core {
44 MOVEIT_CLASS_FORWARD(RobotState);
45 }
46 } // namespace moveit
47 namespace planning_scene {
48 MOVEIT_CLASS_FORWARD(PlanningScene);
49 }
50 namespace robot_trajectory {
51 MOVEIT_CLASS_FORWARD(RobotTrajectory);
52 }
53 namespace Ogre {
54 class SceneNode;
55 }
56 namespace rviz {
57 class DisplayContext;
58 }
59 
60 namespace moveit_rviz_plugin {
61 
62 MOVEIT_CLASS_FORWARD(DisplaySolution);
63 MOVEIT_CLASS_FORWARD(MarkerVisualization);
64 
67 {
69  size_t steps_;
71  planning_scene::PlanningSceneConstPtr start_scene_;
72 
73  struct Data
74  {
76  planning_scene::PlanningSceneConstPtr scene_;
78  robot_trajectory::RobotTrajectoryPtr trajectory_;
80  std::vector<std::string> joints_;
82  std::string comment_;
86  MarkerVisualizationPtr markers_;
87  };
88  std::vector<Data> data_;
89 
90 public:
91  DisplaySolution() = default;
93  DisplaySolution(const DisplaySolution& master, uint32_t sub);
94 
95  size_t numSubSolutions() const { return data_.size(); }
96 
97  size_t getWayPointCount() const { return steps_; }
98  bool empty() const { return steps_ == 0; }
99 
101  using IndexPair = std::pair<size_t, size_t>;
102  IndexPair indexPair(size_t index) const;
103 
104  float getWayPointDurationFromPrevious(const IndexPair& idx_pair) const;
105  float getWayPointDurationFromPrevious(size_t index) const {
106  if (index >= steps_)
107  return 0.1; // display time of last waypoint before switching to final scene
109  }
110  const moveit::core::RobotStatePtr& getWayPointPtr(const IndexPair& idx_pair) const;
111  const moveit::core::RobotStatePtr& getWayPointPtr(size_t index) const { return getWayPointPtr(indexPair(index)); }
112  const planning_scene::PlanningSceneConstPtr& startScene() const { return start_scene_; }
113  const planning_scene::PlanningSceneConstPtr& scene(const IndexPair& idx_pair) const;
114  const planning_scene::PlanningSceneConstPtr& scene(size_t index) const {
115  if (index >= steps_)
116  return data_.back().scene_;
117  return scene(indexPair(index));
118  }
119  const std::string& comment(const IndexPair& idx_pair) const;
120  const std::string& comment(size_t index) const { return comment(indexPair(index)); }
121  uint32_t creatorId(const IndexPair& idx_pair) const;
122 
123  const MarkerVisualizationPtr markers(const IndexPair& idx_pair) const;
124  const MarkerVisualizationPtr markers(size_t index) const { return markers(indexPair(index)); }
125  const MarkerVisualizationPtr markersOfSubTrajectory(size_t index) const { return data_.at(index).markers_; }
126 
127  void setFromMessage(const planning_scene::PlanningScenePtr& start_scene,
128  const moveit_task_constructor_msgs::Solution& msg);
129  void fillMessage(moveit_task_constructor_msgs::Solution& msg) const;
130 };
131 } // namespace moveit_rviz_plugin
moveit_rviz_plugin::DisplaySolution::indexPair
IndexPair indexPair(size_t index) const
Definition: display_solution.cpp:78
moveit_rviz_plugin::DisplaySolution::data_
std::vector< Data > data_
Definition: display_solution.h:88
Ogre
moveit_rviz_plugin::DisplaySolution::comment
const std::string & comment(const IndexPair &idx_pair) const
Definition: display_solution.cpp:109
moveit_rviz_plugin::MOVEIT_CLASS_FORWARD
MOVEIT_CLASS_FORWARD(OcTreeRender)
robot_trajectory::MOVEIT_CLASS_FORWARD
MOVEIT_CLASS_FORWARD(RobotTrajectory)
moveit_rviz_plugin::DisplaySolution::IndexPair
std::pair< size_t, size_t > IndexPair
pair of trajectory part and way point index within part
Definition: display_solution.h:101
moveit_rviz_plugin::DisplaySolution::markers
const MarkerVisualizationPtr markers(size_t index) const
Definition: display_solution.h:124
moveit_rviz_plugin::DisplaySolution::comment
const std::string & comment(size_t index) const
Definition: display_solution.h:120
moveit_rviz_plugin::DisplaySolution::markers
const MarkerVisualizationPtr markers(const IndexPair &idx_pair) const
Definition: display_solution.cpp:117
moveit_rviz_plugin::DisplaySolution::startScene
const planning_scene::PlanningSceneConstPtr & startScene() const
Definition: display_solution.h:112
uint32_t
uint32_t
moveit_rviz_plugin::DisplaySolution
Definition: display_solution.h:66
moveit_rviz_plugin::DisplaySolution::markersOfSubTrajectory
const MarkerVisualizationPtr markersOfSubTrajectory(size_t index) const
Definition: display_solution.h:125
moveit_rviz_plugin::DisplaySolution::Data::scene_
planning_scene::PlanningSceneConstPtr scene_
end scene for each sub trajectory
Definition: display_solution.h:76
moveit_rviz_plugin::DisplaySolution::numSubSolutions
size_t numSubSolutions() const
Definition: display_solution.h:95
moveit_rviz_plugin::DisplaySolution::Data::comment_
std::string comment_
comment of the trajectory
Definition: display_solution.h:82
moveit_rviz_plugin::DisplaySolution::getWayPointCount
size_t getWayPointCount() const
Definition: display_solution.h:97
moveit_rviz_plugin::DisplaySolution::Data::creator_id_
uint32_t creator_id_
id of creating stage
Definition: display_solution.h:84
moveit_rviz_plugin::DisplaySolution::Data::joints_
std::vector< std::string > joints_
joints involved in the trajectory
Definition: display_solution.h:80
moveit_rviz_plugin::DisplaySolution::empty
bool empty() const
Definition: display_solution.h:98
robot_trajectory
moveit_rviz_plugin::DisplaySolution::DisplaySolution
DisplaySolution()=default
planning_scene::MOVEIT_CLASS_FORWARD
MOVEIT_CLASS_FORWARD(PlanningScene)
moveit_rviz_plugin::DisplaySolution::getWayPointDurationFromPrevious
float getWayPointDurationFromPrevious(size_t index) const
Definition: display_solution.h:105
moveit_rviz_plugin::DisplaySolution::steps_
size_t steps_
number of overall steps
Definition: display_solution.h:69
rviz
moveit_rviz_plugin::DisplaySolution::getWayPointDurationFromPrevious
float getWayPointDurationFromPrevious(const IndexPair &idx_pair) const
Definition: display_solution.cpp:96
moveit_rviz_plugin::DisplaySolution::fillMessage
void fillMessage(moveit_task_constructor_msgs::Solution &msg) const
Definition: display_solution.cpp:161
moveit_rviz_plugin::DisplaySolution::Data::markers_
MarkerVisualizationPtr markers_
rviz markers
Definition: display_solution.h:86
moveit_rviz_plugin::DisplaySolution::Data
Definition: display_solution.h:73
moveit_rviz_plugin::DisplaySolution::scene
const planning_scene::PlanningSceneConstPtr & scene(const IndexPair &idx_pair) const
Definition: display_solution.cpp:104
moveit_rviz_plugin
moveit_rviz_plugin::DisplaySolution::getWayPointPtr
const moveit::core::RobotStatePtr & getWayPointPtr(const IndexPair &idx_pair) const
Definition: display_solution.cpp:100
moveit_rviz_plugin::DisplaySolution::start_scene_
planning_scene::PlanningSceneConstPtr start_scene_
start scene
Definition: display_solution.h:71
moveit
class_forward.h
moveit::core::MOVEIT_CLASS_FORWARD
MOVEIT_CLASS_FORWARD(JointModelGroup)
moveit_rviz_plugin::DisplaySolution::getWayPointPtr
const moveit::core::RobotStatePtr & getWayPointPtr(size_t index) const
Definition: display_solution.h:111
moveit_rviz_plugin::DisplaySolution::Data::trajectory_
robot_trajectory::RobotTrajectoryPtr trajectory_
sub trajectories, might be empty
Definition: display_solution.h:78
moveit_rviz_plugin::DisplaySolution::scene
const planning_scene::PlanningSceneConstPtr & scene(size_t index) const
Definition: display_solution.h:114
index
unsigned int index
moveit_rviz_plugin::DisplaySolution::creatorId
uint32_t creatorId(const IndexPair &idx_pair) const
Definition: display_solution.cpp:113
moveit_rviz_plugin::DisplaySolution::setFromMessage
void setFromMessage(const planning_scene::PlanningScenePtr &start_scene, const moveit_task_constructor_msgs::Solution &msg)
Definition: display_solution.cpp:121
planning_scene


visualization
Author(s): Robert Haschke
autogenerated on Thu Feb 27 2025 03:39:51