IRI ROS Specific Algorithm Class. More...
#include <trajectory_2_markers_alg_node.h>
Public Member Functions | |
Trajectory2MarkersAlgNode (void) | |
Constructor. | |
~Trajectory2MarkersAlgNode (void) | |
Destructor. | |
Protected Member Functions | |
void | addNodeDiagnostics (void) |
node add diagnostics | |
void | change_actual_marker (const Eigen::Matrix2d &covs, const double &theta_cov, const geometry_msgs::Point &position, const bool &loopClosure) |
change actual marker | |
visualization_msgs::Marker | create_marker (const uint &id, const std_msgs::Header &header, const Eigen::Matrix2d &covs, const double &theta_cov, const geometry_msgs::Point &position, const bool &loopClosure) const |
create marker | |
void | drawTrajectory (const iri_poseslam::Trajectory &msg) |
fill marker array message | |
visualization_msgs::Marker | get_actual_marker () const |
get actual marker | |
visualization_msgs::MarkerArray | get_covariance_markers () const |
get covariance markers | |
Eigen::Matrix2d | get_ith_cov (const iri_poseslam::Trajectory &msg, const uint i) const |
get ith cov | |
double | get_ith_theta_cov (const iri_poseslam::Trajectory &msg, const uint i) const |
get ith theta cov | |
visualization_msgs::MarkerArray | get_trajectory_marker () const |
get trajectory marker | |
void | initialize_markers () |
initialize line markers | |
void | mainNodeThread (void) |
main node thread | |
void | node_config_update (Config &config, uint32_t level) |
dynamic reconfigure server callback | |
Private Member Functions | |
void | trajectory_callback (const iri_poseslam::Trajectory::ConstPtr &msg) |
Private Attributes | |
visualization_msgs::Marker | actual_marker_ |
ros::Publisher | ActualPoseMarker_publisher_ |
Config | config_ |
visualization_msgs::MarkerArray | covariance_markers_ |
ros::Publisher | CovarianceMarkers_publisher_ |
std::vector< bool > | loop_step_ |
visualization_msgs::Marker | loops_marker_ |
uint | nLoops_ |
visualization_msgs::Marker | trajectory_marker_ |
ros::Subscriber | trajectory_subscriber_ |
ros::Publisher | TrajectoryMarkers_publisher_ |
IRI ROS Specific Algorithm Class.
Definition at line 49 of file trajectory_2_markers_alg_node.h.
Constructor.
This constructor initializes specific class attributes and all ROS communications variables to enable message exchange.
Definition at line 3 of file trajectory_2_markers_alg_node.cpp.
Destructor.
This destructor frees all necessary dynamic memory allocated within this this class.
Definition at line 28 of file trajectory_2_markers_alg_node.cpp.
void Trajectory2MarkersAlgNode::addNodeDiagnostics | ( | void | ) | [protected, virtual] |
node add diagnostics
In this abstract function additional ROS diagnostics applied to the specific algorithms may be added.
Implements algorithm_base::IriBaseAlgorithm< Trajectory2MarkersAlgorithm >.
Definition at line 73 of file trajectory_2_markers_alg_node.cpp.
void Trajectory2MarkersAlgNode::change_actual_marker | ( | const Eigen::Matrix2d & | covs, |
const double & | theta_cov, | ||
const geometry_msgs::Point & | position, | ||
const bool & | loopClosure | ||
) | [protected] |
change actual marker
Definition at line 303 of file trajectory_2_markers_alg_node.cpp.
visualization_msgs::Marker Trajectory2MarkersAlgNode::create_marker | ( | const uint & | id, |
const std_msgs::Header & | header, | ||
const Eigen::Matrix2d & | covs, | ||
const double & | theta_cov, | ||
const geometry_msgs::Point & | position, | ||
const bool & | loopClosure | ||
) | const [protected] |
create marker
Definition at line 249 of file trajectory_2_markers_alg_node.cpp.
void Trajectory2MarkersAlgNode::drawTrajectory | ( | const iri_poseslam::Trajectory & | msg | ) | [protected] |
fill marker array message
Definition at line 135 of file trajectory_2_markers_alg_node.cpp.
visualization_msgs::Marker Trajectory2MarkersAlgNode::get_actual_marker | ( | ) | const [protected] |
get actual marker
Definition at line 239 of file trajectory_2_markers_alg_node.cpp.
visualization_msgs::MarkerArray Trajectory2MarkersAlgNode::get_covariance_markers | ( | ) | const [protected] |
get covariance markers
Definition at line 244 of file trajectory_2_markers_alg_node.cpp.
Eigen::Matrix2d Trajectory2MarkersAlgNode::get_ith_cov | ( | const iri_poseslam::Trajectory & | msg, |
const uint | i | ||
) | const [protected] |
get ith cov
Definition at line 347 of file trajectory_2_markers_alg_node.cpp.
double Trajectory2MarkersAlgNode::get_ith_theta_cov | ( | const iri_poseslam::Trajectory & | msg, |
const uint | i | ||
) | const [protected] |
get ith theta cov
Definition at line 359 of file trajectory_2_markers_alg_node.cpp.
visualization_msgs::MarkerArray Trajectory2MarkersAlgNode::get_trajectory_marker | ( | ) | const [protected] |
get trajectory marker
Definition at line 230 of file trajectory_2_markers_alg_node.cpp.
void Trajectory2MarkersAlgNode::initialize_markers | ( | ) | [protected] |
initialize line markers
Definition at line 83 of file trajectory_2_markers_alg_node.cpp.
void Trajectory2MarkersAlgNode::mainNodeThread | ( | void | ) | [protected, virtual] |
main node thread
This is the main thread node function. Code written here will be executed in every node loop while the algorithm is on running state. Loop frequency can be tuned by modifying loop_rate attribute.
Here data related to the process loop or to ROS topics (mainly data structs related to the MSG and SRV files) must be updated. ROS publisher objects must publish their data in this process. ROS client servers may also request data to the corresponding server topics.
Implements algorithm_base::IriBaseAlgorithm< Trajectory2MarkersAlgorithm >.
Definition at line 33 of file trajectory_2_markers_alg_node.cpp.
void Trajectory2MarkersAlgNode::node_config_update | ( | Config & | config, |
uint32_t | level | ||
) | [protected, virtual] |
dynamic reconfigure server callback
This method is called whenever a new configuration is received through the dynamic reconfigure. The derivated generic algorithm class must implement it.
config | an object with new configuration from all algorithm parameters defined in the config file. |
level | integer referring the level in which the configuration has been changed. |
Implements algorithm_base::IriBaseAlgorithm< Trajectory2MarkersAlgorithm >.
Definition at line 62 of file trajectory_2_markers_alg_node.cpp.
void Trajectory2MarkersAlgNode::trajectory_callback | ( | const iri_poseslam::Trajectory::ConstPtr & | msg | ) | [private] |
Definition at line 42 of file trajectory_2_markers_alg_node.cpp.
visualization_msgs::Marker Trajectory2MarkersAlgNode::actual_marker_ [private] |
Definition at line 60 of file trajectory_2_markers_alg_node.h.
Definition at line 55 of file trajectory_2_markers_alg_node.h.
Config Trajectory2MarkersAlgNode::config_ [private] |
Definition at line 77 of file trajectory_2_markers_alg_node.h.
visualization_msgs::MarkerArray Trajectory2MarkersAlgNode::covariance_markers_ [private] |
Definition at line 57 of file trajectory_2_markers_alg_node.h.
Definition at line 53 of file trajectory_2_markers_alg_node.h.
std::vector<bool> Trajectory2MarkersAlgNode::loop_step_ [private] |
Definition at line 74 of file trajectory_2_markers_alg_node.h.
visualization_msgs::Marker Trajectory2MarkersAlgNode::loops_marker_ [private] |
Definition at line 58 of file trajectory_2_markers_alg_node.h.
uint Trajectory2MarkersAlgNode::nLoops_ [private] |
Definition at line 75 of file trajectory_2_markers_alg_node.h.
visualization_msgs::Marker Trajectory2MarkersAlgNode::trajectory_marker_ [private] |
Definition at line 59 of file trajectory_2_markers_alg_node.h.
Definition at line 63 of file trajectory_2_markers_alg_node.h.
Definition at line 54 of file trajectory_2_markers_alg_node.h.