moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
trajectory_display.hpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2015, University of Colorado, Boulder
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 the Univ of CO, Boulder 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: Dave Coleman
36 Desc: Wraps a trajectory_visualization playback class for Rviz into a stand alone display
37*/
38
39#pragma once
40
41#include <rclcpp/version.h>
42
43#include <rviz_common/display.hpp>
44#include <rviz_common/display_context.hpp>
45#include <rviz_common/ros_integration/ros_node_abstraction_iface.hpp>
46
48#ifndef Q_MOC_RUN
49#include <rclcpp/rclcpp.hpp>
51#endif
52
53#include <chrono>
54
55namespace rviz_common
56{
57class DisplayContext;
58}
59
60namespace moveit_rviz_plugin
61{
62class TrajectoryDisplay : public rviz_common::Display
63{
64 Q_OBJECT
65 // friend class TrajectoryVisualization; // allow the visualization class to access the display
66
67public:
69
71
72 void loadRobotModel();
73
74 void load(const rviz_common::Config& config) override;
75
76 // For Rolling, L-turtle, and newer
77#if RCLCPP_VERSION_GTE(30, 0, 0)
78 using rviz_common::Display::update;
79 // `using` handles update(float, float) deprecation warning and redirect
80 void update(std::chrono::nanoseconds wall_dt, std::chrono::nanoseconds ros_dt) override;
81// For Kilted and older
82#else
83 void update(float wall_dt, float ros_dt) override;
84#endif
85
86 void reset() override;
87
88 // overrides from Display
89 void onInitialize() override;
90 void onEnable() override;
91 void onDisable() override;
92
93private Q_SLOTS:
97 void changedRobotDescription();
98
99protected:
100 // The trajectory playback component
101 TrajectoryVisualizationPtr trajectory_visual_;
102
103 // Load robot model
104 rdf_loader::RDFLoaderPtr rdf_loader_;
105 moveit::core::RobotModelConstPtr robot_model_;
106 moveit::core::RobotStatePtr robot_state_;
107
108 // Properties
109 rviz_common::properties::StringProperty* robot_description_property_;
110
111 rclcpp::Node::SharedPtr node_;
112 rclcpp::Logger logger_;
113};
114
115} // namespace moveit_rviz_plugin
void load(const rviz_common::Config &config) override
moveit::core::RobotModelConstPtr robot_model_
TrajectoryVisualizationPtr trajectory_visual_
void update(float wall_dt, float ros_dt) override
rviz_common::properties::StringProperty * robot_description_property_