Abstract class for the Cafer client Main functionnalities: More...
#include <component.hpp>
Public Member Functions | |
Component (std::string mgmt_topic, std::string _type, double freq=10, bool new_nodehandle=false) | |
constructor of Component More... | |
~Component (void) | |
virtual void | update ()=0 |
update Calls the code to take into account what has been received through the subscribers (typically update parameter values by taking into account received values) More... | |
virtual void | client_connect_to_ros ()=0 |
connect_to_ros all the definition of subscriber and publisher must be done in this method. WARNING: this is not called by default. It is usually called in the init() method. More... | |
virtual void | client_disconnect_from_ros ()=0 |
disconnect_from_ros the purpose of this methode is to free the memory of all subscribers and publishers shared_ptrof the node. WARNING: this is not called by default. Is is usually called in the destructor. More... | |
virtual void | init ()=0 |
init the purpose of this method is to make whatever initialization required. More... | |
virtual bool | is_initialized () |
is_initialized More... | |
bool | get_terminate (void) const |
get_terminate return true if the client is down and false otherwise More... | |
std::string | get_type (void) const |
Get type of the client. More... | |
long int | get_id (void) const |
Accessor to the client id (unique) More... | |
bool | is_connected_to_ros () const |
this method inform if the subcriber, publisher or server are up or not. More... | |
void | connect_to_ros (void) |
Connect the client to ROD, i.e. intantiate subscribers, publishers and services. More... | |
void | disconnect_from_ros (void) |
Disconnect the client from ROS, i.e. destroy subscribers and publishers. More... | |
void | shutdown (void) |
Shutting down the component and the corresponding node. More... | |
std::string | call_launch_file (std::string launch_file, std::string namespace_base, std::string management_topic="") |
Call a launch file. Corresponding nodes are to be launched in a namespace namespace_base_XX where XX is a unique id (provided by the getid service). It will be connected to the management_topic topic (the same than this class if this argument equals ""). More... | |
void | sleep (void) |
Sleep: should be called by the user code once all the things that have to be done during one iteration of the loop have been done. More... | |
void | spin (void) |
encapsulation of ros::spinOnce() More... | |
unsigned int | how_many_client_from_type (std::string _type, bool up_only=true) |
Check the number of client nodes that have been observed up to now (watchdog) and return their number. If up_only is set to true, only the nodes that are up are counted, otherwise, they are all counted. More... | |
void | get_connected_client_with_type (std::string _type, std::vector< ClientDescriptor > &vcd, bool up_only=true) |
Get the ClientDescriptors of all clients connected to the same management topic and of a certain type. More... | |
bool | is_it_recent_enough (ros::Time t) |
Check if a given time is "recent" or not with respect to the node client frequency. More... | |
bool | is_client_up (std::string ns, long int id) |
Check whether a client is up or not (relies on the watchdog functionnality, works only for nodes that are on the same management topic) More... | |
void | wait_for_client (std::string ns, long int id) |
Waits until the client is up (it needs to be on the same management topic) More... | |
void | wait_for_init (void) |
Waits for the initialization from the client specific side. More... | |
std::string | get_namespace (void) const |
Gets node namespace. More... | |
CreatedNodes_t & | get_created_nodes (void) |
Gets the created_nodes. More... | |
std::vector< ClientDescriptor > & | get_created_nodes (std::string created_ns) |
Gets the created_nodes. More... | |
void | kill_created_nodes (void) |
kill all nodes created by this component More... | |
void | management_cb (const cafer_core::Management &mgmt) |
Management callback: what to do when a management message is received. More... | |
void | ask_new_ack () |
ask for acknowledgement to all nodes that are handled by this Component More... | |
void | ack_creation () |
Creation of an acknowledgement to respond to an ask for acknowledgment. More... | |
void | update_watchdog (std::string ns, long int id, std::string _type) |
What to do when a watchdog message is received: update the corresponding time in the watchdog map. More... | |
ros::Time | get_watchdog (std::string ns, long int id) |
Get the time of the last watchdog message for a particular client. More... | |
void | watchdog_cb (const ros::TimerEvent &event) |
Send a watchdog message telling that the client is still alive... More... | |
void | send_complete_node_death (std::string ns, long int id) |
send a request of death to a specific client More... | |
void | send_local_node_death (std::string ns, long int id) |
send a request for client to disconect him from ros More... | |
Public Attributes | |
MapWatchDog_t | map_watchdog |
CreatedNodes_t | created_nodes |
shared_ptr< NodeHandle > | my_ros_nh |
shared_ptr< ros::CallbackQueue > | my_ros_queue |
shared_ptr< Subscriber > | management_s |
shared_ptr< Publisher > | management_p |
Protected Attributes | |
int | id |
std::string | type |
int | creator_id |
std::string | creator_ns |
std::string | created_ns |
std::string | _mgmt_topic |
bool | terminate |
shared_ptr< ros::Rate > | rate |
shared_ptr< ros::Timer > | watchdog |
bool | _is_init = false |
bool | _is_connected_to_ros = false |
Abstract class for the Cafer client Main functionnalities:
Definition at line 110 of file component.hpp.
cafer_core::Component::Component | ( | std::string | mgmt_topic, |
std::string | _type, | ||
double | freq = 10 , |
||
bool | new_nodehandle = false |
||
) |
constructor of Component
management | topic |
type | of this component |
frequence | of update. 10 by default. |
true | if a new nodehandle must be created. false by default |
|
inline |
Definition at line 124 of file component.hpp.
void cafer_core::Component::ack_creation | ( | ) |
Creation of an acknowledgement to respond to an ask for acknowledgment.
void cafer_core::Component::ask_new_ack | ( | ) |
ask for acknowledgement to all nodes that are handled by this Component
std::string cafer_core::Component::call_launch_file | ( | std::string | launch_file, |
std::string | namespace_base, | ||
std::string | management_topic = "" |
||
) |
Call a launch file. Corresponding nodes are to be launched in a namespace namespace_base_XX where XX is a unique id (provided by the getid service). It will be connected to the management_topic topic (the same than this class if this argument equals "").
name | of the launch file |
base | name of general namespace |
name | of the management topic |
|
pure virtual |
connect_to_ros all the definition of subscriber and publisher must be done in this method. WARNING: this is not called by default. It is usually called in the init() method.
|
pure virtual |
disconnect_from_ros the purpose of this methode is to free the memory of all subscribers and publishers shared_ptrof the node. WARNING: this is not called by default. Is is usually called in the destructor.
|
inline |
Connect the client to ROD, i.e. intantiate subscribers, publishers and services.
Definition at line 196 of file component.hpp.
|
inline |
Disconnect the client from ROS, i.e. destroy subscribers and publishers.
Definition at line 206 of file component.hpp.
void cafer_core::Component::get_connected_client_with_type | ( | std::string | _type, |
std::vector< ClientDescriptor > & | vcd, | ||
bool | up_only = true |
||
) |
Get the ClientDescriptors of all clients connected to the same management topic and of a certain type.
type | of clients | |
[out] | vector | of client descriptor |
if | true, consider only the clients that are up. true by default |
|
inline |
|
inline |
|
inline |
Accessor to the client id (unique)
Definition at line 183 of file component.hpp.
|
inline |
|
inline |
get_terminate return true if the client is down and false otherwise
Should the client terminate ? This needs to be taken into account in the user code
Definition at line 168 of file component.hpp.
|
inline |
ros::Time cafer_core::Component::get_watchdog | ( | std::string | ns, |
long int | id | ||
) |
Get the time of the last watchdog message for a particular client.
namespace | of client |
id | of client |
unsigned int cafer_core::Component::how_many_client_from_type | ( | std::string | _type, |
bool | up_only = true |
||
) |
Check the number of client nodes that have been observed up to now (watchdog) and return their number. If up_only is set to true, only the nodes that are up are counted, otherwise, they are all counted.
_type | of components that we want to check |
up_only | boolean. true by default. |
|
pure virtual |
init the purpose of this method is to make whatever initialization required.
|
inline |
Check whether a client is up or not (relies on the watchdog functionnality, works only for nodes that are on the same management topic)
namespace | of the client |
id | of the client |
Definition at line 278 of file component.hpp.
|
inline |
this method inform if the subcriber, publisher or server are up or not.
Definition at line 190 of file component.hpp.
|
inlinevirtual |
is_initialized
Definition at line 158 of file component.hpp.
bool cafer_core::Component::is_it_recent_enough | ( | ros::Time | t | ) |
Check if a given time is "recent" or not with respect to the node client frequency.
the | time to check |
void cafer_core::Component::kill_created_nodes | ( | void | ) |
kill all nodes created by this component
void cafer_core::Component::management_cb | ( | const cafer_core::Management & | mgmt | ) |
Management callback: what to do when a management message is received.
management | message |
void cafer_core::Component::send_complete_node_death | ( | std::string | ns, |
long int | id | ||
) |
send a request of death to a specific client
namespace | of client |
id | of client |
void cafer_core::Component::send_local_node_death | ( | std::string | ns, |
long int | id | ||
) |
send a request for client to disconect him from ros
namespace | of client |
id | of client |
|
inline |
Shutting down the component and the corresponding node.
Definition at line 218 of file component.hpp.
|
inline |
Sleep: should be called by the user code once all the things that have to be done during one iteration of the loop have been done.
Definition at line 238 of file component.hpp.
void cafer_core::Component::spin | ( | void | ) |
encapsulation of ros::spinOnce()
|
pure virtual |
update Calls the code to take into account what has been received through the subscribers (typically update parameter values by taking into account received values)
void cafer_core::Component::update_watchdog | ( | std::string | ns, |
long int | id, | ||
std::string | _type | ||
) |
What to do when a watchdog message is received: update the corresponding time in the watchdog map.
namespace | of client checked |
id | of checked client |
type | of checked client |
void cafer_core::Component::wait_for_client | ( | std::string | ns, |
long int | id | ||
) |
Waits until the client is up (it needs to be on the same management topic)
namespace | of client |
id | of client |
void cafer_core::Component::wait_for_init | ( | void | ) |
Waits for the initialization from the client specific side.
void cafer_core::Component::watchdog_cb | ( | const ros::TimerEvent & | event | ) |
Send a watchdog message telling that the client is still alive...
event |
|
protected |
Definition at line 408 of file component.hpp.
|
protected |
Definition at line 407 of file component.hpp.
|
protected |
Definition at line 396 of file component.hpp.
CreatedNodes_t cafer_core::Component::created_nodes |
map in which are stored all nodes created by a call_launch_file. The key is the required namespace
Definition at line 379 of file component.hpp.
|
protected |
Definition at line 395 of file component.hpp.
|
protected |
Definition at line 393 of file component.hpp.
|
protected |
Definition at line 394 of file component.hpp.
|
protected |
Definition at line 391 of file component.hpp.
shared_ptr<Publisher> cafer_core::Component::management_p |
publisher to the management topic
Definition at line 387 of file component.hpp.
shared_ptr<Subscriber> cafer_core::Component::management_s |
subscriber to the management topic
Definition at line 385 of file component.hpp.
MapWatchDog_t cafer_core::Component::map_watchdog |
map in which is stored the last watchdog message received from each client connected to the management topic of this client
Definition at line 376 of file component.hpp.
shared_ptr<NodeHandle> cafer_core::Component::my_ros_nh |
Definition at line 381 of file component.hpp.
shared_ptr<ros::CallbackQueue> cafer_core::Component::my_ros_queue |
Definition at line 382 of file component.hpp.
|
protected |
ROS update rate
Definition at line 400 of file component.hpp.
|
protected |
did we receive the order to stop the client ?
Definition at line 397 of file component.hpp.
|
protected |
Definition at line 392 of file component.hpp.
|
protected |
Watchdog
Definition at line 402 of file component.hpp.