SplineVisual.h
Go to the documentation of this file.
1 /***************************************************************************
2  * Software License Agreement (BSD License) *
3  * Copyright (C) 2016 by George Todoran <george.todoran@tuwien.ac.at> *
4  * *
5  * Redistribution and use in source and binary forms, with or without *
6  * modification, are permitted provided that the following conditions *
7  * are met: *
8  * *
9  * 1. Redistributions of source code must retain the above copyright *
10  * notice, this list of conditions and the following disclaimer. *
11  * 2. Redistributions in binary form must reproduce the above copyright *
12  * notice, this list of conditions and the following disclaimer in *
13  * the documentation and/or other materials provided with the *
14  * distribution. *
15  * 3. Neither the name of the copyright holder nor the names of its *
16  * contributors may be used to endorse or promote products derived *
17  * from this software without specific prior written permission. *
18  * *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS *
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT *
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS *
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE *
23  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, *
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, *
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; *
26  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER *
27  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT *
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY *
29  * WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE *
30  * POSSIBILITY OF SUCH DAMAGE. *
31  ***************************************************************************/
32 
33 #ifndef SPLINE_VISUAL_H
34 #define SPLINE_VISUAL_H
35 
36 #include <tuw_nav_msgs/Spline.h>
38 #include <eigen3/unsupported/Eigen/Splines>
40 #include <tuw_control/state/state_sim_template.hpp>
41 
42 namespace Ogre
43 {
44 class Vector3;
45 class Quaternion;
46 }
47 
48 namespace rviz
49 {
50 class Shape;
51 }
52 
53 namespace tuw {
54 class MetricSplineSim : public StateSimTemplate<2,1> {
55 
56  public : enum class StateVars { SIGMA, ARC, ENUM_SIZE };
57  public : enum class StateNmVars { SIGMA, ENUM_SIZE };
58  public : enum class StateCfVars { ARC, ENUM_SIZE };
59 
61 
62  public : StateSimUPtr cloneStateSim () const override;
63  public : double stateArc () const override;
64  public : double stateDist () const override;
65  public : ParamFuncs* paramFuncs () override;
66  public : ParamFuncsDist* paramFuncsDist () override;
67 
68  private : void setStateCf ( const double& _arc, const ParamFuncs::EvalArcGuarantee& _evalArcGuarantee = ParamFuncs::EvalArcGuarantee::AFTER_LAST ) override;
69  private : State& stateNmDelta ( const double& _dArc ) override { throw "not implemented"; }
70  private : State& stateNmDot () override;
71 
74 };
75 }
76 
77 namespace tuw_nav_rviz
78 {
79 
80 // Declare the visual class for this display.
82 {
83 public:
84  // Constructor. Creates the visual stuff and puts it into the
85  // scene, but in an unconfigured state.
86  SplineVisual( Ogre::SceneManager* scene_manager, Ogre::SceneNode* parent_node );
87 
88  // Destructor. Removes the visual stuff from the scene.
89  virtual ~SplineVisual();
90 
91  // Configure the visual to show the data in the message.
92  void setMessage( const tuw_nav_msgs::Spline::ConstPtr& msg );
93 
94  // Set the pose of the coordinate frame the message refers to.
95  // These could be done inside setMessage(), but that would require
96  // calls to FrameManager and error handling inside setMessage(),
97  // which doesn't seem as clean. This way SplineVisual is
98  // only responsible for visualization.
99  void setFramePosition( const Ogre::Vector3& position );
100  void setFrameOrientation( const Ogre::Quaternion& orientation );
101 
102  // Set the color of the visual, which is an user-editable
103  // parameter and therefore don't come from the MarkerDetection message.
104  void setPathColor( Ogre::ColourValue color );
105  void setOrientColor( Ogre::ColourValue color );
106 
107  // Set the shape of the visual, which is an user-editable
108  // parameter and therefore don't come from the MarkerDetection message.
109  void setShape( rviz::Shape::Type shape_type );
110 
111  // Set the scale of the visual, which is an user-editable
112  // parameter and therefore don't come from the MarkerDetection message.
113  void setPathScale ( float scale );
114  void setOrientScale( float scale );
115 
116  void setPathDs ( float _ds );
117  void setOrientDs ( float _ds );
118 
119 private:
120  // The objects implementing the actual shape
121  std::vector<boost::shared_ptr<rviz::Shape> > splinePtsXY_;
122  std::vector<boost::shared_ptr<rviz::Arrow> > splinePtsTheta_;
123 
125  std::shared_ptr<tuw::MetricSplineSim> metricSplineSim_;
126  std::vector<double> sigmaXYLattice_;
127  std::vector<double> sigmaThetaLattice_;
128 
129  // A SceneNode whose pose is set to match the coordinate frame of
130  // the Imu message header.
131  Ogre::SceneNode* frame_node_;
132 
133  // The SceneManager, kept here only so the destructor can ask it to
134  // destroy the ``frame_node_``.
135  Ogre::SceneManager* scene_manager_;
136 
137  // The Shape object's color
138  Ogre::ColourValue colorPath_;
139  Ogre::ColourValue colorOrient_;
140 
141  // The Shape object's shape type
143 
144  // The Shape object's scale
145  float scalePath_;
147 
148  float dsPathXY_;
150 };
151 
152 } // end namespace tuw_nav_rviz
153 
154 #endif // SPLINE_VISUAL_H
rviz::Shape::Type shape_type_
Definition: SplineVisual.h:142
Ogre::SceneNode * frame_node_
Definition: SplineVisual.h:131
Ogre::ColourValue colorOrient_
Definition: SplineVisual.h:139
std::vector< boost::shared_ptr< rviz::Arrow > > splinePtsTheta_
Definition: SplineVisual.h:122
Ogre::ColourValue colorPath_
Definition: SplineVisual.h:138
boost::shared_ptr< Eigen::Spline3d > spline3d_
Parametric functions with closed-form distance evaluation structure.
Definition: SplineVisual.h:73
std::vector< double > sigmaXYLattice_
Definition: SplineVisual.h:126
State & stateNmDelta(const double &_dArc) override
Definition: SplineVisual.h:69
std::vector< double > sigmaThetaLattice_
Definition: SplineVisual.h:127
std::shared_ptr< tuw::MetricSplineSim > metricSplineSim_
Definition: SplineVisual.h:125
boost::shared_ptr< Eigen::Spline3d > spline_
Definition: SplineVisual.h:124
std::vector< boost::shared_ptr< rviz::Shape > > splinePtsXY_
Definition: SplineVisual.h:121
TFSIMD_FORCE_INLINE Vector3()
Ogre::SceneManager * scene_manager_
Definition: SplineVisual.h:135


tuw_nav_rviz
Author(s):
autogenerated on Mon Jun 10 2019 15:40:12