Public Types | Public Member Functions | Public Attributes | Private Member Functions | Private Attributes
WamDriver Class Reference

IRI ROS Specific Driver Class. More...

#include <wam_driver.h>

Inheritance diagram for WamDriver:
Inheritance graph
[legend]

List of all members.

Public Types

typedef iri_wam_wrapper::WamConfig Config
 define config type

Public Member Functions

bool closeDriver (void)
 close driver
void config_update (const Config &new_cfg, uint32_t level=0)
 config update
void dmp_tracker_new_goal (const std::vector< double > *new_goal)
trajectory_msgs::JointTrajectoryPoint get_desired_joint_trajectory_point ()
 Returns the current desired joint trajectory point.
const boost::shared_ptr
< ForceRequest
get_force_request_info ()
 return a reference to current force request info
void get_joint_angles (std::vector< double > *angles)
int get_num_joints ()
void get_pose (std::vector< double > *pose)
std::string get_robot_name ()
void hold_current_position (bool on)
bool is_joint_trajectory_result_succeeded ()
bool is_moving ()
 check if the wam is moving right now
void jnt_pos_cmd_callback (const std::vector< float > *joints, const std::vector< float > *rate_limits)
void move_in_cartesian_pose (const geometry_msgs::Pose pose, const double vel=0, const double acc=0)
 Ask the low level driver to perform a movement to reach cartesian pose.
void move_in_joints (std::vector< double > *angles, std::vector< double > *vels=NULL, std::vector< double > *accs=NULL)
void move_trajectory_in_joints (const trajectory_msgs::JointTrajectory &trajectory)
 Ask the low level driver to perform a trajectory in joints.
void move_trajectory_learnt_and_estimate_force (const std::string model_filename, const std::string points_filename)
 Ask the low level driver to perform a LWPR trajectory and return force estimation.
bool openDriver (void)
 open driver
void start_dmp_tracker (const std::vector< double > *initial, const std::vector< double > *goal)
 Starts the DMP tracker.
bool startDriver (void)
 start driver
void stop_trajectory_in_joints ()
bool stopDriver (void)
 stop driver
void wait_move_end ()
 WamDriver ()
 constructor
 ~WamDriver ()
 Destructor.

Public Attributes

Config config_
 config variable

Private Member Functions

bool is_joints_move_request_valid (const std::vector< double > &angles)
 check if move in joints request is sane

Private Attributes

trajectory_msgs::JointTrajectoryPoint desired_joint_trajectory_point_
boost::shared_ptr< ForceRequestforce_request_
std::string robot_name_
int server_port
int state_refresh_rate
wamDriver * wam_
std::string wamserver_ip

Detailed Description

IRI ROS Specific Driver Class.

This class inherits from the IRI Base class IriBaseDriver, which provides the guidelines to implement any specific driver. The IriBaseDriver class offers an easy framework to integrate functional drivers implemented in C++ with the ROS driver structure. ROS driver_base state transitions are already managed by IriBaseDriver.

The WamDriver class must implement all specific driver requirements to safetely open, close, run and stop the driver at any time. It also must guarantee an accessible interface for all driver's parameters.

The WamConfig.cfg needs to be filled up with those parameters suitable to be changed dynamically by the ROS dyanmic reconfigure application. The implementation of the CIriNode class will manage those parameters through methods like postNodeOpenHook() and reconfigureNodeHook().

Definition at line 91 of file wam_driver.h.


Member Typedef Documentation

typedef iri_wam_wrapper::WamConfig WamDriver::Config

define config type

Define a Config type with the WamConfig. All driver implementations will then use the same variable type Config.

Definition at line 122 of file wam_driver.h.


Constructor & Destructor Documentation

constructor

In this constructor parameters related to the specific driver can be initalized. Those parameters can be also set in the openDriver() function. Attributes from the main node driver class IriBaseDriver such as loop_rate, may be also overload here.

Definition at line 7 of file wam_driver.cpp.

Destructor.

This destructor is called when the object is about to be destroyed.

Definition at line 138 of file wam_driver.cpp.


Member Function Documentation

bool WamDriver::closeDriver ( void  ) [virtual]

close driver

In this function, the driver must be closed. Variables related to the driver state must also be taken into account. This function is automatically called by IriBaseDriver::doClose(), an state transition is performed if return value equals true.

Returns:
bool successful

Implements iri_base_driver::IriBaseDriver.

Definition at line 87 of file wam_driver.cpp.

void WamDriver::config_update ( const Config new_cfg,
uint32_t  level = 0 
)

config update

In this function the driver parameters must be updated with the input config variable. Then the new configuration state will be stored in the Config attribute.

Parameters:
new_cfgthe new driver configuration state
levellevel in which the update is taken place

Definition at line 125 of file wam_driver.cpp.

void WamDriver::dmp_tracker_new_goal ( const std::vector< double > *  new_goal)

Definition at line 384 of file wam_driver.cpp.

trajectory_msgs::JointTrajectoryPoint WamDriver::get_desired_joint_trajectory_point ( )

Returns the current desired joint trajectory point.

Definition at line 261 of file wam_driver.cpp.

const boost::shared_ptr<ForceRequest> WamDriver::get_force_request_info ( ) [inline]

return a reference to current force request info

Definition at line 270 of file wam_driver.h.

void WamDriver::get_joint_angles ( std::vector< double > *  angles)

Definition at line 184 of file wam_driver.cpp.

Definition at line 148 of file wam_driver.cpp.

void WamDriver::get_pose ( std::vector< double > *  pose)

Definition at line 178 of file wam_driver.cpp.

std::string WamDriver::get_robot_name ( )

Definition at line 143 of file wam_driver.cpp.

Definition at line 254 of file wam_driver.cpp.

Definition at line 162 of file wam_driver.cpp.

bool WamDriver::is_joints_move_request_valid ( const std::vector< double > &  angles) [private]

check if move in joints request is sane

Control if the vector has the same size of robot joints and if there is no Nan values

Definition at line 190 of file wam_driver.cpp.

check if the wam is moving right now

Definition at line 155 of file wam_driver.cpp.

void WamDriver::jnt_pos_cmd_callback ( const std::vector< float > *  joints,
const std::vector< float > *  rate_limits 
)

Definition at line 408 of file wam_driver.cpp.

void WamDriver::move_in_cartesian_pose ( const geometry_msgs::Pose  pose,
const double  vel = 0,
const double  acc = 0 
)

Ask the low level driver to perform a movement to reach cartesian pose.

This funcion will translate from geometry_pose to low level format and call the low level driver function to perform the cartesian move

Definition at line 236 of file wam_driver.cpp.

void WamDriver::move_in_joints ( std::vector< double > *  angles,
std::vector< double > *  vels = NULL,
std::vector< double > *  accs = NULL 
)

Definition at line 211 of file wam_driver.cpp.

void WamDriver::move_trajectory_in_joints ( const trajectory_msgs::JointTrajectory &  trajectory)

Ask the low level driver to perform a trajectory in joints.

This functions will translate from joint trajectory message to low level driver types and sent the command to perform the trajectory given by the joint positions.

Definition at line 268 of file wam_driver.cpp.

void WamDriver::move_trajectory_learnt_and_estimate_force ( const std::string  model_filename,
const std::string  points_filename 
)

Ask the low level driver to perform a LWPR trajectory and return force estimation.

This function will send to the low level driver the request to use the files which contains an LWPR model and trajectory points. It will perform the trajectory and return the estimate force at the end

Parameters:
model_filename,:full server system path which contains the LWPR model
points_filename,:full server system path which contains the points for the trajectory

Definition at line 331 of file wam_driver.cpp.

bool WamDriver::openDriver ( void  ) [virtual]

open driver

In this function, the driver must be openned. Openning errors must be taken into account. This function is automatically called by IriBaseDriver::doOpen(), an state transition is performed if return value equals true.

Returns:
bool successful

Implements iri_base_driver::IriBaseDriver.

Definition at line 57 of file wam_driver.cpp.

void WamDriver::start_dmp_tracker ( const std::vector< double > *  initial,
const std::vector< double > *  goal 
)

Starts the DMP tracker.

Definition at line 343 of file wam_driver.cpp.

bool WamDriver::startDriver ( void  ) [virtual]

start driver

After this function, the driver and its thread will be started. The driver and related variables should be properly setup. This function is automatically called by IriBaseDriver::doStart(), an state transition is performed if return value equals true.

Returns:
bool successful

Implements iri_base_driver::IriBaseDriver.

Definition at line 96 of file wam_driver.cpp.

Definition at line 325 of file wam_driver.cpp.

bool WamDriver::stopDriver ( void  ) [virtual]

stop driver

After this function, the driver's thread will stop its execution. The driver and related variables should be properly setup. This function is automatically called by IriBaseDriver::doStop(), an state transition is performed if return value equals true.

Returns:
bool successful

Implements iri_base_driver::IriBaseDriver.

Definition at line 116 of file wam_driver.cpp.

Definition at line 172 of file wam_driver.cpp.


Member Data Documentation

config variable

This variable has all the driver parameters defined in the cfg config file. Is updated everytime function config_update() is called.

Definition at line 130 of file wam_driver.h.

trajectory_msgs::JointTrajectoryPoint WamDriver::desired_joint_trajectory_point_ [private]

Definition at line 105 of file wam_driver.h.

boost::shared_ptr<ForceRequest> WamDriver::force_request_ [private]

Object for handling force estimation request process

Definition at line 103 of file wam_driver.h.

std::string WamDriver::robot_name_ [private]

Definition at line 95 of file wam_driver.h.

int WamDriver::server_port [private]

Definition at line 97 of file wam_driver.h.

Definition at line 98 of file wam_driver.h.

wamDriver* WamDriver::wam_ [private]

Definition at line 99 of file wam_driver.h.

std::string WamDriver::wamserver_ip [private]

Definition at line 96 of file wam_driver.h.


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


iri_wam_wrapper
Author(s): Pol Monso
autogenerated on Fri Dec 6 2013 21:47:20