Public Member Functions | Protected Member Functions | Static Protected Member Functions | Private Member Functions | Private Attributes
PlatformTeleopAlgNode Class Reference

IRI ROS Specific Algorithm Class. More...

#include <platform_teleop_alg_node.h>

Inheritance diagram for PlatformTeleopAlgNode:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 PlatformTeleopAlgNode (void)
 Constructor.
 ~PlatformTeleopAlgNode (void)
 Destructor.

Protected Member Functions

void addNodeDiagnostics (void)
 node add diagnostics
geometry_msgs::Twist generateTwist (void)
 generate twist
void mainNodeThread (void)
 main node thread
void node_config_update (Config &config, uint32_t level)
 dynamic reconfigure server callback
void useAxes (const float &axe_value, const unsigned int &index)
 use button
bool useButton (const unsigned int &index)
 use button
void useExtraButton (const unsigned int &index)
 use extra button

Static Protected Member Functions

static bool check_movement_axes_callback (const std::vector< float > &axes, std::vector< unsigned int > &index)
 check used axes

Private Member Functions

void joy_callback (const sensor_msgs::Joy::ConstPtr &joy_msg)

Private Attributes

bool check_human_
 check or not if human is alive
ros::Publisher cmd_vel_publisher_
float dVR_
 translational increment velocity
float dVT_
 translational increment velocity
bool human_is_alive_
 Tells if the human user is alive.
CMutex joy_mutex_
ros::Subscriber joy_subscriber_
std::vector< int > prev_axes_
 last used joystick axes
std::vector< int > prev_buttons_
 last pressed joysting buttons
float vR_
 rotational velocity
float vT_
 translational velocity

Detailed Description

IRI ROS Specific Algorithm Class.

Definition at line 43 of file platform_teleop_alg_node.h.


Constructor & Destructor Documentation

Constructor.

This constructor initializes specific class attributes and all ROS communications variables to enable message exchange.

Definition at line 5 of file platform_teleop_alg_node.cpp.

Destructor.

This destructor frees all necessary dynamic memory allocated within this this class.

Definition at line 32 of file platform_teleop_alg_node.cpp.


Member Function Documentation

void PlatformTeleopAlgNode::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< PlatformTeleopAlgorithm >.

Definition at line 120 of file platform_teleop_alg_node.cpp.

bool PlatformTeleopAlgNode::check_movement_axes_callback ( const std::vector< float > &  axes,
std::vector< unsigned int > &  index 
) [static, protected]

check used axes

This function receives a vector with the state from all joystick axes. If none of the axes has been used, returns false, otherwise returns a vector with the indexes for the used axes.

Parameters:
axesvector with the current state of each axe
indexvector with the indexes for each used axe
Returns:
bool true if at least one axe has been updated, false otherwise

Definition at line 124 of file platform_teleop_alg_node.cpp.

geometry_msgs::Twist PlatformTeleopAlgNode::generateTwist ( void  ) [protected]

generate twist

This function fills up a twist message with current translational and rotational velocities (vT, vR).

Returns:
Twist twist message with last updated state

Definition at line 142 of file platform_teleop_alg_node.cpp.

void PlatformTeleopAlgNode::joy_callback ( const sensor_msgs::Joy::ConstPtr &  joy_msg) [private]

Definition at line 50 of file platform_teleop_alg_node.cpp.

void PlatformTeleopAlgNode::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< PlatformTeleopAlgorithm >.

Definition at line 37 of file platform_teleop_alg_node.cpp.

void PlatformTeleopAlgNode::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.

Parameters:
configan object with new configuration from all algorithm parameters defined in the config file.
levelinteger referring the level in which the configuration has been changed.

Implements algorithm_base::IriBaseAlgorithm< PlatformTeleopAlgorithm >.

Definition at line 111 of file platform_teleop_alg_node.cpp.

void PlatformTeleopAlgNode::useAxes ( const float &  axe_value,
const unsigned int &  index 
) [protected]

use button

This function receives the value of a single axe and its index and triggers corresponding action defined.

Parameters:
axe_valueaxe value
indexjoystick button index

Definition at line 244 of file platform_teleop_alg_node.cpp.

bool PlatformTeleopAlgNode::useButton ( const unsigned int &  index) [protected]

use button

This function receives a single button index and updates current state according to the behavior defined. Updates velocities according to axes and calls useExtraButton for further actions with other buttons.

Parameters:
indexjoystick button index

Definition at line 152 of file platform_teleop_alg_node.cpp.

void PlatformTeleopAlgNode::useExtraButton ( const unsigned int &  index) [protected]

use extra button

This function receives a single button index and updates current state according to the behavior defined. Called by useButton, for pruposes beyond navigation.

Parameters:
indexjoystick button index

Definition at line 219 of file platform_teleop_alg_node.cpp.


Member Data Documentation

check or not if human is alive

If this option is true, the user has to press the button B all time in order to give velocity to the robot

Definition at line 112 of file platform_teleop_alg_node.h.

Definition at line 47 of file platform_teleop_alg_node.h.

float PlatformTeleopAlgNode::dVR_ [private]

translational increment velocity

Rotational platform velocity in [rad/s] to increment vR_.

Definition at line 88 of file platform_teleop_alg_node.h.

float PlatformTeleopAlgNode::dVT_ [private]

translational increment velocity

Translational platform velocity in [m/s] to increment vT_.

Definition at line 81 of file platform_teleop_alg_node.h.

Tells if the human user is alive.

Depending on the button B this will be true or false. This is an option through check_human_

Definition at line 120 of file platform_teleop_alg_node.h.

Definition at line 52 of file platform_teleop_alg_node.h.

Definition at line 50 of file platform_teleop_alg_node.h.

last used joystick axes

Vector with indexes to last used axes to avoid multiple commands without releasing a button.

Definition at line 104 of file platform_teleop_alg_node.h.

last pressed joysting buttons

Vector with indexes to last joystick pressed buttons to avoid multiple commands without releasing a button.

Definition at line 96 of file platform_teleop_alg_node.h.

float PlatformTeleopAlgNode::vR_ [private]

rotational velocity

Rotational platform velocity in [rad/s] to be published with twist.

Definition at line 74 of file platform_teleop_alg_node.h.

float PlatformTeleopAlgNode::vT_ [private]

translational velocity

Translational platform velocity in [m/s] to be published with twist.

Definition at line 67 of file platform_teleop_alg_node.h.


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


iri_platform_teleop
Author(s): Joan Perez, jnperez at iri.upc.edu
autogenerated on Fri Dec 6 2013 20:29:09