dynamic_graph_manager
dynamic_graph::DynamicGraphManager Class Reference

This class has for purpose to manage the different processes during run time. More...

#include <dynamic_graph_manager.hh>

Inheritance diagram for dynamic_graph::DynamicGraphManager:

Public Member Functions

 DynamicGraphManager ()
 DynamicGraphManager, constructor of the class.
 
virtual ~DynamicGraphManager ()
 DynamicGraphManager, destructor of the class.
 
void initialize (YAML::Node param)
 initialize the basic variables
 
void run ()
 run() splits the process in the dynamic_graph process and the hadware_communication process. More...
 
void wait_start_dynamic_graph ()
 wait_start_dynamic_graph put the current thread to sleep until the user start the dynamic graph
 
void wait_stop_dynamic_graph ()
 wait_stop_dynamic_graph put the current thread to sleep until the user stop the dynamic graph
 
void wait_stop_hardware_communication ()
 wait_stop_hardware_communication put the current thread to sleep until the user stop the hardware communication. More...
 
void initialize_dynamic_graph_process ()
 initialize_dynamic_graph_process instanciates all variables related to the dynamic_graph and user interface.
 
void run_python_command (std::ostream &file, const std::string &command)
 run_python_command More...
 
void python_prologue ()
 python_prologue get the pointer of the device in the the python interpretor.
 
virtual void run_dynamic_graph_process ()
 run_dynamic_graph_process spawns the real time thread and becomes a ros spinner (thread in charge of the ros::service callbacks). More...
 
virtual void run_hardware_communication_process ()
 run_hardware_communication_process spawns the real time thread. More...
 
virtual void run_single_process ()
 run_single_process spawns the real time thread. More...
 
virtual void initialize_hardware_communication_process ()
 initialize_hardware_communication_process instanciate all variables related to the hardware communication. More...
 
virtual void get_sensors_to_map (VectorDGMap &)
 get_sensors_to_map is the fonction that get the motor command from a map and that uses the drivers to send these command to the robot. More...
 
virtual void set_motor_controls_from_map (const VectorDGMap &)
 set_motor_controls_from_map is the fonction that get the motor command from a map and that uses the drivers to send these command to the robot. More...
 
virtual void compute_safety_controls ()
 compute_safety_controls computes safety controls very fast in case the dynamic graph is taking to much computation time or has crashed.
 
void stop_dynamic_graph ()
 stop_dynamic_graph stop the DynamicGraph. More...
 
void start_dynamic_graph ()
 start_dynamic_graph start the DynamicGraph. More...
 
bool is_dynamic_graph_stopped ()
 get the status of the dynamic graph (is running or not) More...
 
void stop_hardware_communication ()
 stop_hardware_communication stops the hardware communication. More...
 
void start_hardware_communication ()
 start_hardware_communication starts the hardware communication. More...
 
bool is_hardware_communication_stopped ()
 get the status of the hardware communication (is running or not). More...
 
pid_t pid_dynamic_graph_process ()
 pid_dynamic_graph_process is an accessor on the pid of the process More...
 
pid_t pid_hardware_communication_process ()
 pid_hardware_communication_process is an accessor on the pid of the process More...
 
Devicedevice ()
 device is a getter method on the Device internal pointer. More...
 
bool has_dynamic_graph_process_died ()
 has_dynamic_graph_process_died check if the process of the DynamicGraph has died or not. More...
 
virtual bool is_in_safety_mode ()
 is_in_safety_mode check if the dynamic graph is still alive and sending commands at a descent frequency. More...
 

Static Public Attributes

static const std::string dg_ros_node_name_ = "dynamic_graph"
 dg_ros_node_name_ this is the ros node name of the dynamic graph process
 
static const std::string hw_com_ros_node_name_
 hw_com_ros_node_name_ this is the ros node name of the harware communication process More...
 
static const std::string shared_memory_name_ = "DGM_ShM"
 shared_memory_name is the name of the shared memory segment to be used
 
static const std::string sensors_map_name_ = "sensors_map"
 sensors_map_name is the name of the sensor map inside the shared memory segment
 
static const std::string motor_controls_map_name_
 motor_controls_map_name is the name of the motor controls map inside the shared memory segment More...
 
static const std::string cond_var_name_ = "cond_var"
 cond_var_sensors_name_ is the name of the condition variable in the shared memory
 

Protected Member Functions

void add_user_command (std::function< void(void)> func)
 Method inherited. More...
 

Protected Attributes

ros::ServiceServer ros_service_start_dg_
 ros_service_start_dg_ allows to start the dynamic graph on call. More...
 
ros::ServiceServer ros_service_stop_dg_
 ros_service_stop_dg_ allows to stop the dynamic graph on call. More...
 
std::atomic< bool > is_dynamic_graph_stopped_
 is_dynamic_graph_stopped_ is the flag reflecting the state of the dynamic graph. More...
 
std::atomic< bool > is_hardware_communication_stopped_
 is_hardware_communication_stopped_ is the flag reflecting the state of the hardware communication thread. More...
 
std::unique_ptr< dynamic_graph::RosPythonInterpreterros_python_interpreter_
 ros_python_interpreter_ptr_ is a ROS wrapper around a python interpreter.
 
std::unique_ptr< real_time_tools::RealTimeThread > thread_dynamic_graph_
 thread_dynamic_graph_ is the real time thread that runs the dynamic graph.
 
std::unique_ptr< real_time_tools::RealTimeThread > thread_hardware_communication_
 thread_hardware_communication_ is the real thread that communicate with the hardware.
 
pid_t pid_dynamic_graph_process_
 pid_dynamic_graph_process_ is the pid of the DynamicGraph process. More...
 
pid_t pid_hardware_communication_process_
 pid_hardware_communication_process_ is the pid of the hardware communication process. More...
 
std::unique_ptr< Devicedevice_
 device_ is the DynamicGraph device that manages the computation of the graph.
 
VectorDGMap sensors_map_
 sensors_map_ is a map of dynamicgraph::Vector. More...
 
VectorDGMap motor_controls_map_
 motor_controls_map_ is a map of dynamicgraph::Vector. More...
 
std::unique_ptr< shared_memory::LockedConditionVariable > cond_var_
 cond_var_sensors_ this condition variable allow the computation of the dynamic graph just after the acquisition of the sensors
 
bool has_been_waken_by_dg_
 has_been_waken_by_dg_ is a flag that indicates if the hardware communication process has been awaken by the dynamic_graph process or not.
 
unsigned missed_control_count_
 missed_control_count_ is counting the number of iteration when the dynamic_graph failed to provide data.
 
unsigned max_missed_control_
 max_missed_control_ if the missed_control_count_ reach the value of max_missed_control_ then we switch to safety mode.
 
clock::duration control_period_
 control_period_ this is the control period in nanoseconds.
 
clock::time_point hw_time_loop_before_sleep_
 hw_time_loop_before_sleep_ is the time measurement just before the hardware communication loop goes to sleep.
 
clock::time_point hw_time_loop_after_sleep_
 hw_time_loop_after_sleep_ is the time measurement just after the hardware communication loop goes to sleep.
 
clock::duration hw_meas_sleep_time_
 hw_measured_sleep_time_ is the time during which the hardware communication process actually slept.
 
clock::duration hw_ref_sleep_time_
 hw_ref_sleep_time_ is the time during which the hardware communication process is supposed to sleep.
 
clock::duration hw_meas_active_time_
 hw_meas_active_time_ is the time during which the hardware communication process is supposed to sleep.
 
bool is_real_robot_
 is_real_robot this boolean is a parameter to indicate if yes or no we are in simulation or in a real robot mode.
 
std::string dg_active_timer_file_
 dg_active_timer_file_ this is the path to the file that will contain the computation time of each of the dynamic graph complete execution.
 
std::string dg_sleep_timer_file_
 dg_sleep_timer_file_ this is the path to the file that will contain the sleep duration of the dynamic graph thread.
 
std::string dg_timer_file_
 dg_timer_file_ this is the path to the file that will contain the time of the dynamic graph loop.
 
std::string hwc_active_timer_file_
 hwc_active_timer_file_ this is the path to the file that will contain the computation time of each active period of the hardware communication loop.
 
std::string hwc_sleep_timer_file_
 hwc_sleep_timer_file_ this is the path to the file that will contain the sleeping time of the hardware communication loop.
 
std::string hwc_timer_file_
 hwc_timer_file_ this is the path to the file that will contain the computation time of each of the hardware communication complete execution.
 
std::string log_dir_
 log_folder_ is the folder where all the data of the current experiment will be saved.
 
std::string python_log_file_
 This file will contain the python interpreter output.
 
std::string app_dir_
 This is the application directory in the home directory.
 
real_time_tools::Timer dg_active_timer_
 dg_active_timer_ is the timer measuring the computation time of the dynamic graph loop.
 
real_time_tools::Timer dg_sleep_timer_
 dg_sleep_timer_ is the timer measuring the time during which the dynamic graph loop sleeps.
 
real_time_tools::Timer dg_timer_
 dg_timer_ is the timer measuring the duration time of the dynamic graph loop.
 
real_time_tools::Timer hwc_active_timer_
 hwc_active_timer is measuring the active time of the hardware communication loop
 
real_time_tools::Timer hwc_sleep_timer_
 hwc_sleep_timer is measuring the sleeping time of the hardware communication loop
 
real_time_tools::Timer hwc_timer_
 hwc_timer is measuring the time of the hardware communication loop
 
unsigned memory_buffer_timers_
 memory_buffer_timers_ is the size of the memory buffers for the real_time_tools timers.
 
real_time_tools::Spinner hwc_spinner_
 This class allows us to time the real time thread for the hardware communication.
 
double hwc_predicted_sleeping_time_
 This corresponds to the predicted sleeping time for the hardware communication process. More...
 
double maximum_time_for_user_cmd_
 This the duration during which a user command can be executed.
 
std::deque< std::function< void(void)> > user_commands_
 This is the list of the user commands.
 
std::deque< ros::ServiceServer > ros_user_commands_
 Attribute shared with the daughter class. More...
 
double control_period_sec_
 control_period_sec_ this is the control period in Seconds (S.I. More...
 
YAML::Node params_
 params_ is the pool of parameters in a yaml tree
 
std::mutex hwc_mutex_
 

Private Member Functions

bool start_dynamic_graph (std_srvs::Empty::Request &, std_srvs::Empty::Response &)
 Method NOT inherited. More...
 
bool stop_dynamic_graph (std_srvs::Empty::Request &, std_srvs::Empty::Response &)
 stop_dg is the callback method of the ROS service stop dynamic graph More...
 
void start_ros_service (ros::NodeHandle &ros_node_handle)
 start_ros_service is the method that advertise the different ros services.
 
void * dynamic_graph_real_time_loop ()
 dynamic_graph_real_time_loop is the method used to execute the dynamic graph.
 
void * hardware_communication_real_time_loop ()
 hardware_communication_real_time_loop is the method that communicate with the hardware and send the commands (torque, position, current, ...)
 
void * single_process_real_time_loop ()
 single_process_real_time_loop is the method that performs the control but in one single process. More...
 

Static Private Member Functions

static void * dynamic_graph_real_time_loop_helper (void *context)
 dynamic_graph_real_time_loop_helper is a static member allowing to use the posix pthread_create. More...
 
static void * hardware_communication_real_time_loop_helper (void *context)
 dynamic_graph_real_time_loop_helper is a static member allowing to use the posix pthread_create. More...
 
static void * single_process_real_time_loop_helper (void *context)
 dynamic_graph_real_time_loop_helper is a static member allowing to use the posix pthread_create. More...
 

Detailed Description

This class has for purpose to manage the different processes during run time.

The main tasks are:

  • [1] Creates the Dynamic Graph device, the python interpreter, and the Drivers
  • [2] Ask the python interpreter to advertise its ROS services
  • [3] Ask the drivers to initialize the communication with the hardware
  • [4] Loads a yaml/urdf config file.
  • [5] Advertise the ROS services start/stop dynamic graph
  • [6] Wait for the ROS service start dynamic graph to be called
  • [7] Spawn the first real time process that executes the following:
    • [7.1] gets the sensor data using Drivers and saves them in the shared std::map sensors
    • [7.2] reads the control values in the shared std::map commands and send them to the motors via the Drivers
  • [8] Spawn the second real time process that executes the following:
    • [8.1] passes the std::map sensors to the Device, which copies the data to its output signals
    • [8.2] gets the control values from the Device (which triggers the evaluation of the dynamic graph) and copies them into the shared std::map commands. In this class we heavily depend on std::unique pointers in order to initialize the DynamicGraph process and the hardware communication process independently.
Examples:
simple_dgm.hpp.

Member Function Documentation

◆ add_user_command()

void DynamicGraphManager::add_user_command ( std::function< void(void)>  func)
protected

Method inherited.

This method allow to simply add a user command

Examples:
simple_dgm.hpp.

◆ device()

Device& dynamic_graph::DynamicGraphManager::device ( )
inline

device is a getter method on the Device internal pointer.

Returns
a const reference to the device.

◆ dynamic_graph_real_time_loop_helper()

static void* dynamic_graph::DynamicGraphManager::dynamic_graph_real_time_loop_helper ( void *  context)
inlinestaticprivate

dynamic_graph_real_time_loop_helper is a static member allowing to use the posix pthread_create.

Parameters
contextis the DynamicGraphManager that spawned the thread.
Returns
nothing interesting for us.

◆ get_sensors_to_map()

virtual void dynamic_graph::DynamicGraphManager::get_sensors_to_map ( VectorDGMap )
inlinevirtual

get_sensors_to_map is the fonction that get the motor command from a map and that uses the drivers to send these command to the robot.

Each robot must have a different implementation of this function. WARNING, this function needs to be overloaded using the actual drivers of the robot.

Reimplemented in dynamic_graph_manager::SimpleDGM.

◆ hardware_communication_real_time_loop_helper()

static void* dynamic_graph::DynamicGraphManager::hardware_communication_real_time_loop_helper ( void *  context)
inlinestaticprivate

dynamic_graph_real_time_loop_helper is a static member allowing to use the posix pthread_create.

Parameters
contextis the DynamicGraphManager that spawned the thread.
Returns
nothing interesting for us.

◆ has_dynamic_graph_process_died()

bool DynamicGraphManager::has_dynamic_graph_process_died ( )

has_dynamic_graph_process_died check if the process of the DynamicGraph has died or not.

Returns
true if the DynamicGraph process died.

◆ initialize_hardware_communication_process()

virtual void dynamic_graph::DynamicGraphManager::initialize_hardware_communication_process ( )
inlinevirtual

initialize_hardware_communication_process instanciate all variables related to the hardware communication.

In addition it spawns the real time thread. WARNING, this function needs to be overloaded using the actual drivers of the robot.

Reimplemented in dynamic_graph_manager::SimpleDGM.

◆ is_dynamic_graph_stopped()

bool dynamic_graph::DynamicGraphManager::is_dynamic_graph_stopped ( )
inline

get the status of the dynamic graph (is running or not)

Returns
the flag is_dynamic_graph_stopped_ value

◆ is_hardware_communication_stopped()

bool dynamic_graph::DynamicGraphManager::is_hardware_communication_stopped ( )
inline

get the status of the hardware communication (is running or not).

Returns
the flags is_dynamic_graph_stopped_ value.

◆ is_in_safety_mode()

virtual bool dynamic_graph::DynamicGraphManager::is_in_safety_mode ( )
inlinevirtual

is_in_safety_mode check if the dynamic graph is still alive and sending commands at a descent frequency.

Returns
true if there is a problem

Reimplemented in dynamic_graph_manager::SimpleDGM.

◆ pid_dynamic_graph_process()

pid_t dynamic_graph::DynamicGraphManager::pid_dynamic_graph_process ( )
inline

pid_dynamic_graph_process is an accessor on the pid of the process

Returns
the pid of the dynamic graph process

◆ pid_hardware_communication_process()

pid_t dynamic_graph::DynamicGraphManager::pid_hardware_communication_process ( )
inline

pid_hardware_communication_process is an accessor on the pid of the process

Returns
the pid of the dynamic graph process

◆ run()

void DynamicGraphManager::run ( )

run() splits the process in the dynamic_graph process and the hadware_communication process.

It initialize them and run them. WARNING this a NONE blocking function. One can spin endlessly using the ROS: ros::waitForShutdown(), for example.

Examples:
main.cpp.

◆ run_dynamic_graph_process()

void DynamicGraphManager::run_dynamic_graph_process ( )
virtual

run_dynamic_graph_process spawns the real time thread and becomes a ros spinner (thread in charge of the ros::service callbacks).

This function is virtual has it might differ from os to os.

◆ run_hardware_communication_process()

void DynamicGraphManager::run_hardware_communication_process ( )
virtual

run_hardware_communication_process spawns the real time thread.

WARNING this function is not blocking. Function to block are available like ros::waitForShutdown() for example. This function is virtual has it might differ from os to os.

◆ run_python_command()

void DynamicGraphManager::run_python_command ( std::ostream &  file,
const std::string &  command 
)

run_python_command

Parameters
fileis the logging file to log the entry
commandis the python command itself

◆ run_single_process()

void DynamicGraphManager::run_single_process ( )
virtual

run_single_process spawns the real time thread.

WARNING this function is not blocking. Function to block are available like ros::waitForShutdown() for example. This function is virtual has it might differ from os to os.

◆ set_motor_controls_from_map()

virtual void dynamic_graph::DynamicGraphManager::set_motor_controls_from_map ( const VectorDGMap )
inlinevirtual

set_motor_controls_from_map is the fonction that get the motor command from a map and that uses the drivers to send these command to the robot.

Each robot must have a different implementation of this function. WARNING, this function needs to be overloaded using the actual drivers of the robot.

Reimplemented in dynamic_graph_manager::SimpleDGM.

◆ single_process_real_time_loop()

void * DynamicGraphManager::single_process_real_time_loop ( )
private

single_process_real_time_loop is the method that performs the control but in one single process.

(torque, position, current, ...)

◆ single_process_real_time_loop_helper()

static void* dynamic_graph::DynamicGraphManager::single_process_real_time_loop_helper ( void *  context)
inlinestaticprivate

dynamic_graph_real_time_loop_helper is a static member allowing to use the posix pthread_create.

Parameters
contextis the DynamicGraphManager that spawned the thread.
Returns
nothing interesting for us.

◆ start_dynamic_graph() [1/2]

void dynamic_graph::DynamicGraphManager::start_dynamic_graph ( )
inline

start_dynamic_graph start the DynamicGraph.

;)

◆ start_dynamic_graph() [2/2]

bool dynamic_graph::DynamicGraphManager::start_dynamic_graph ( std_srvs::Empty::Request &  ,
std_srvs::Empty::Response &   
)
inlineprivate

Method NOT inherited.

start_dg is the callback method of the ROS service start dynamic graph.

Returns
true.

◆ start_hardware_communication()

void dynamic_graph::DynamicGraphManager::start_hardware_communication ( )
inline

start_hardware_communication starts the hardware communication.

;)

◆ stop_dynamic_graph() [1/2]

void dynamic_graph::DynamicGraphManager::stop_dynamic_graph ( )
inline

stop_dynamic_graph stop the DynamicGraph.

;)

◆ stop_dynamic_graph() [2/2]

bool dynamic_graph::DynamicGraphManager::stop_dynamic_graph ( std_srvs::Empty::Request &  ,
std_srvs::Empty::Response &   
)
inlineprivate

stop_dg is the callback method of the ROS service stop dynamic graph

Returns

◆ stop_hardware_communication()

void dynamic_graph::DynamicGraphManager::stop_hardware_communication ( )
inline

stop_hardware_communication stops the hardware communication.

;)

◆ wait_stop_hardware_communication()

void DynamicGraphManager::wait_stop_hardware_communication ( )

wait_stop_hardware_communication put the current thread to sleep until the user stop the hardware communication.

&& hw_com_ros_node.ok()

Member Data Documentation

◆ control_period_sec_

double dynamic_graph::DynamicGraphManager::control_period_sec_
protected

control_period_sec_ this is the control period in Seconds (S.I.

units) for computation.

◆ hw_com_ros_node_name_

const std::string DynamicGraphManager::hw_com_ros_node_name_
static
Initial value:
=
"hardware_communication"

hw_com_ros_node_name_ this is the ros node name of the harware communication process

Examples:
simple_dgm.hpp.

◆ hwc_predicted_sleeping_time_

double dynamic_graph::DynamicGraphManager::hwc_predicted_sleeping_time_
protected

This corresponds to the predicted sleeping time for the hardware communication process.

If this time is bigger than a certain threshold then user commands to the hardware can be sent.

◆ is_dynamic_graph_stopped_

std::atomic<bool> dynamic_graph::DynamicGraphManager::is_dynamic_graph_stopped_
protected

is_dynamic_graph_stopped_ is the flag reflecting the state of the dynamic graph.

  • TRUE the Dynamic Graph is NOT running.
  • FALSE the Dynamic Graph IS running. The type "atomic" is here to make sure that this variable is thread safe

◆ is_hardware_communication_stopped_

std::atomic<bool> dynamic_graph::DynamicGraphManager::is_hardware_communication_stopped_
protected

is_hardware_communication_stopped_ is the flag reflecting the state of the hardware communication thread.

  • TRUE the hardware communication is NOT running.
  • FALSE the hardware communication IS running. The type "atomic" is here to make sure that this variable is thread safe

◆ motor_controls_map_

VectorDGMap dynamic_graph::DynamicGraphManager::motor_controls_map_
protected

motor_controls_map_ is a map of dynamicgraph::Vector.

They represent all the controls to be sent to the robot.

Examples:
simple_dgm.hpp.

◆ motor_controls_map_name_

const std::string DynamicGraphManager::motor_controls_map_name_
static
Initial value:
=
"motor_controls_map"

motor_controls_map_name is the name of the motor controls map inside the shared memory segment

◆ pid_dynamic_graph_process_

pid_t dynamic_graph::DynamicGraphManager::pid_dynamic_graph_process_
protected

pid_dynamic_graph_process_ is the pid of the DynamicGraph process.

It is initialized to 0 and set during the DynamicGraphManager::run method

◆ pid_hardware_communication_process_

pid_t dynamic_graph::DynamicGraphManager::pid_hardware_communication_process_
protected

pid_hardware_communication_process_ is the pid of the hardware communication process.

It is initialized to 0 and set during the DynamicGraphManager::run method

◆ ros_service_start_dg_

ros::ServiceServer dynamic_graph::DynamicGraphManager::ros_service_start_dg_
protected

ros_service_start_dg_ allows to start the dynamic graph on call.

It simply sets a flags that is used to wait the user call. Only used in the dynamic_graph process.

◆ ros_service_stop_dg_

ros::ServiceServer dynamic_graph::DynamicGraphManager::ros_service_stop_dg_
protected

ros_service_stop_dg_ allows to stop the dynamic graph on call.

It simply sets a flags that stop the main real time the control loop. Only used in the dynamic_graph process.

◆ ros_user_commands_

std::deque<ros::ServiceServer> dynamic_graph::DynamicGraphManager::ros_user_commands_
protected

Attribute shared with the daughter class.

This is the list of the ros user commands. The class inheriting from this one can add services for the hardware communication process.

Examples:
simple_dgm.hpp.

◆ sensors_map_

VectorDGMap dynamic_graph::DynamicGraphManager::sensors_map_
protected

sensors_map_ is a map of dynamicgraph::Vector.

They represent all the sensors data measured on the robot.


The documentation for this class was generated from the following files: