Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025 #ifndef _trajectory_to_markers_alg_h_
00026 #define _trajectory_to_markers_alg_h_
00027
00028 #include <iri_trajectory_to_markers/TrajectoryToMarkersConfig.h>
00029 #include "mutex.h"
00030 #include <Eigen/Core>
00031 #include <Eigen/Eigenvalues>
00032
00033
00034 #include <visualization_msgs/MarkerArray.h>
00035 #include <iri_nav_msgs/Trajectory.h>
00036 #include <tf/transform_broadcaster.h>
00037 #include <tf/transform_datatypes.h>
00038
00044 class TrajectoryToMarkersAlgorithm
00045 {
00046 protected:
00053 CMutex alg_mutex_;
00054
00055 private:
00056 visualization_msgs::MarkerArray marker_array_;
00057 visualization_msgs::Marker loops_marker_;
00058 visualization_msgs::Marker trajectory_marker_;
00059 visualization_msgs::Marker actual_marker_;
00060 std::vector<bool> loop_state_;
00061 uint nLoops_;
00062
00063 public:
00070 typedef iri_trajectory_to_markers::TrajectoryToMarkersConfig Config;
00071
00078 Config config_;
00079
00088 TrajectoryToMarkersAlgorithm(void);
00089
00095 void lock(void) { alg_mutex_.enter(); };
00096
00102 void unlock(void) { alg_mutex_.exit(); };
00103
00111 bool try_enter(void) { return alg_mutex_.try_enter(); };
00112
00124 void config_update(Config& new_cfg, uint32_t level=0);
00125
00126
00127
00128
00135 ~TrajectoryToMarkersAlgorithm(void);
00136
00139 void initialize_markers();
00140
00143 bool drawCovariances(const iri_nav_msgs::Trajectory& msg);
00144
00147 visualization_msgs::MarkerArray get_marker_array() const;
00148
00151 visualization_msgs::Marker get_actual_marker() const;
00152
00155 visualization_msgs::Marker create_marker(const uint& id, const std_msgs::Header& header, const Eigen::Matrix2f& covs, const float& theta_cov, const geometry_msgs::Point& position, const bool& loopClosure) const;
00156
00159 void change_actual_marker(const Eigen::Matrix2f& covs, const float& theta_cov, const geometry_msgs::Point& position, const bool& loopClosure);
00160
00163 visualization_msgs::Marker create_loop_marker(const uint& id, const std_msgs::Header& header, const geometry_msgs::Point& position1, const geometry_msgs::Point& position2) const;
00164
00167 Eigen::Matrix2f get_ith_cov(const iri_nav_msgs::Trajectory& msg, const uint i) const;
00168
00171 float get_ith_theta_cov(const iri_nav_msgs::Trajectory& msg, const uint i) const;
00172 };
00173
00174 #endif