IRI ROS Specific Algorithm Class. More...
#include <laser_navigation_alg_node.h>
Public Member Functions | |
LaserNavigationAlgNode (void) | |
Constructor. | |
~LaserNavigationAlgNode (void) | |
Destructor. | |
Protected Member Functions | |
void | addNodeDiagnostics (void) |
node add diagnostics | |
void | mainNodeThread (void) |
main node thread | |
void | node_config_update (Config &config, uint32_t level) |
dynamic reconfigure server callback | |
void | ROS_INFO_PRESS (const std::string &str) |
void | ROS_INFO_XYR (const std::string &str, const float &x, const float &y, const geometry_msgs::Quaternion &r) |
void | ROS_INFO_XYR (const std::string &str, const tf::Transform &tftrans) |
Private Member Functions | |
bool | load_path_ (const std::string &bag_path) |
void | publish_marker (const geometry_msgs::PoseStamped &pose, const int &type) |
void | scan_callback (const sensor_msgs::LaserScan::ConstPtr &msg) |
void | send_goalActive () |
void | send_goalDone (const actionlib::SimpleClientGoalState &state, const move_base_msgs::MoveBaseResultConstPtr &result) |
void | send_goalFeedback (const move_base_msgs::MoveBaseFeedbackConstPtr &feedback) |
void | send_goalMakeActionRequest (const geometry_msgs::PoseStamped &new_goal) |
Private Attributes | |
ros::Publisher | checkpoints_publisher_ |
uint | current_ |
ros::ServiceClient | estimate_client_ |
iri_laser_localisation::DoEstimation | estimate_srv_ |
bool | first_ |
sensor_msgs::LaserScan | LaserScan_msg_ |
ros::ServiceClient | localise_client_ |
iri_laser_localisation::DoLocalisation | localise_srv_ |
visualization_msgs::Marker | Marker_msg_ |
bool | new_scan_ |
std::vector < geometry_msgs::PoseStamped > | pose_path_ |
ros::Publisher | pose_ref_publisher_ |
CMutex | scan_mutex_ |
std::vector < sensor_msgs::LaserScan > | scan_path_ |
sensor_msgs::LaserScan | scan_sens_ |
ros::Subscriber | scan_subscriber_ |
ros::Publisher | scans_map_publisher_ |
actionlib::SimpleActionClient < move_base_msgs::MoveBaseAction > | send_goal_client_ |
tf::TransformBroadcaster | tfb_ |
bool | waiting_ |
IRI ROS Specific Algorithm Class.
Definition at line 58 of file laser_navigation_alg_node.h.
Constructor.
This constructor initializes specific class attributes and all ROS communications variables to enable message exchange.
this->scans_ref_publisher_ = this->public_node_handle_.advertise<sensor_msgs::LaserScan>("scans_ref", 100);
Definition at line 4 of file laser_navigation_alg_node.cpp.
Destructor.
This destructor frees all necessary dynamic memory allocated within this this class.
Definition at line 36 of file laser_navigation_alg_node.cpp.
void LaserNavigationAlgNode::addNodeDiagnostics | ( | void | ) | [protected, virtual] |
node add diagnostics
void ROS_INFO_XYR(const std::string & str,const tf::Transform & tftrans); In this abstract function additional ROS diagnostics applied to the specific algorithms may be added.
Implements algorithm_base::IriBaseAlgorithm< LaserNavigationAlgorithm >.
Definition at line 327 of file laser_navigation_alg_node.cpp.
bool LaserNavigationAlgNode::load_path_ | ( | const std::string & | bag_path | ) | [private] |
---------------- LOAD PATH ---------------------------------------------
Definition at line 341 of file laser_navigation_alg_node.cpp.
void LaserNavigationAlgNode::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.
---------------- main THREAD -------------------------------------------
---- ONLY IN FIRST RUN ----
---- LOAD PATH ----
---- ESTIMATE FIRST POSE ----
---- PUBLISH MARKERS ----
---- MAP PREVIEW ----
Here the robot is localised with the following pose
___________________________ LOOP _________________________________________
---- WAIT FOR NEW SCANS ----
---- MOVE ----
Update the next goal Send it to Move Base & wait until it reaches (or not) it
If it has reached the last goal, wait until the program is closed
---- SENSE ----
Localise the robot
Here the robot is localised with the following pose
Implements algorithm_base::IriBaseAlgorithm< LaserNavigationAlgorithm >.
Definition at line 43 of file laser_navigation_alg_node.cpp.
void LaserNavigationAlgNode::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< LaserNavigationAlgorithm >.
Definition at line 320 of file laser_navigation_alg_node.cpp.
void LaserNavigationAlgNode::publish_marker | ( | const geometry_msgs::PoseStamped & | pose, |
const int & | type | ||
) | [private] |
---------------- PUBLISH MARKER ----------------------------------------
Definition at line 393 of file laser_navigation_alg_node.cpp.
void LaserNavigationAlgNode::ROS_INFO_PRESS | ( | const std::string & | str | ) | [protected] |
Definition at line 429 of file laser_navigation_alg_node.cpp.
void LaserNavigationAlgNode::ROS_INFO_XYR | ( | const std::string & | str, |
const float & | x, | ||
const float & | y, | ||
const geometry_msgs::Quaternion & | r | ||
) | [protected] |
Definition at line 436 of file laser_navigation_alg_node.cpp.
void LaserNavigationAlgNode::ROS_INFO_XYR | ( | const std::string & | str, |
const tf::Transform & | tftrans | ||
) | [protected] |
Definition at line 443 of file laser_navigation_alg_node.cpp.
void LaserNavigationAlgNode::scan_callback | ( | const sensor_msgs::LaserScan::ConstPtr & | msg | ) | [private] |
Definition at line 221 of file laser_navigation_alg_node.cpp.
void LaserNavigationAlgNode::send_goalActive | ( | ) | [private] |
Definition at line 248 of file laser_navigation_alg_node.cpp.
void LaserNavigationAlgNode::send_goalDone | ( | const actionlib::SimpleClientGoalState & | state, |
const move_base_msgs::MoveBaseResultConstPtr & | result | ||
) | [private] |
Definition at line 238 of file laser_navigation_alg_node.cpp.
void LaserNavigationAlgNode::send_goalFeedback | ( | const move_base_msgs::MoveBaseFeedbackConstPtr & | feedback | ) | [private] |
Definition at line 253 of file laser_navigation_alg_node.cpp.
void LaserNavigationAlgNode::send_goalMakeActionRequest | ( | const geometry_msgs::PoseStamped & | new_goal | ) | [private] |
---------------- SEND GOAL ----------------------------------------------
Definition at line 273 of file laser_navigation_alg_node.cpp.
Definition at line 65 of file laser_navigation_alg_node.h.
uint LaserNavigationAlgNode::current_ [private] |
Definition at line 96 of file laser_navigation_alg_node.h.
Definition at line 78 of file laser_navigation_alg_node.h.
iri_laser_localisation::DoEstimation LaserNavigationAlgNode::estimate_srv_ [private] |
Definition at line 79 of file laser_navigation_alg_node.h.
bool LaserNavigationAlgNode::first_ [private] |
Definition at line 99 of file laser_navigation_alg_node.h.
sensor_msgs::LaserScan LaserNavigationAlgNode::LaserScan_msg_ [private] |
Definition at line 63 of file laser_navigation_alg_node.h.
Definition at line 76 of file laser_navigation_alg_node.h.
iri_laser_localisation::DoLocalisation LaserNavigationAlgNode::localise_srv_ [private] |
Definition at line 77 of file laser_navigation_alg_node.h.
visualization_msgs::Marker LaserNavigationAlgNode::Marker_msg_ [private] |
Definition at line 66 of file laser_navigation_alg_node.h.
bool LaserNavigationAlgNode::new_scan_ [private] |
Definition at line 97 of file laser_navigation_alg_node.h.
std::vector<geometry_msgs::PoseStamped> LaserNavigationAlgNode::pose_path_ [private] |
Definition at line 95 of file laser_navigation_alg_node.h.
Definition at line 64 of file laser_navigation_alg_node.h.
CMutex LaserNavigationAlgNode::scan_mutex_ [private] |
Definition at line 71 of file laser_navigation_alg_node.h.
std::vector<sensor_msgs::LaserScan> LaserNavigationAlgNode::scan_path_ [private] |
Definition at line 94 of file laser_navigation_alg_node.h.
sensor_msgs::LaserScan LaserNavigationAlgNode::scan_sens_ [private] |
Definition at line 93 of file laser_navigation_alg_node.h.
Definition at line 69 of file laser_navigation_alg_node.h.
Definition at line 62 of file laser_navigation_alg_node.h.
actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction> LaserNavigationAlgNode::send_goal_client_ [private] |
Definition at line 84 of file laser_navigation_alg_node.h.
Definition at line 101 of file laser_navigation_alg_node.h.
bool LaserNavigationAlgNode::waiting_ [private] |
Definition at line 98 of file laser_navigation_alg_node.h.