Public Member Functions | Protected Attributes
shadowrobot::MovementPublisher Class Reference

#include <movement_publisher.hpp>

List of all members.

Public Member Functions

void add_movement (PartialMovement mvt)
void calculateErrorCallback (const sr_robot_msgs::JointControllerState::ConstPtr &msg)
void execute_step (int index_mvt_step, int index_partial_movement)
 MovementPublisher (double min_value=0.0, double max_value=1.5, double rate=100.0, unsigned int repetition=1, unsigned int nb_mvt_step=1000, std::string controller_type="")
void pr2_calculateErrorCallback (const pr2_controllers_msgs::JointControllerState::ConstPtr &msg)
void set_publisher (ros::Publisher publisher)
void start ()
void stop ()
virtual ~MovementPublisher ()

Protected Attributes

std::string controller_type
double last_target_
double max
double min
double MSError_
std_msgs::Float64 msg
unsigned int n_samples_
unsigned int nb_mvt_step
ros::NodeHandle nh_tilde
std::vector< PartialMovementpartial_movements
ros::Publisher pub
ros::Publisher pub_2
ros::Rate publishing_rate
unsigned int repetition
double SError_
ros::Subscriber sub_

Detailed Description

Definition at line 41 of file movement_publisher.hpp.


Constructor & Destructor Documentation

shadowrobot::MovementPublisher::MovementPublisher ( double  min_value = 0.0,
double  max_value = 1.5,
double  rate = 100.0,
unsigned int  repetition = 1,
unsigned int  nb_mvt_step = 1000,
std::string  controller_type = "" 
)

Definition at line 33 of file movement_publisher.cpp.

Definition at line 58 of file movement_publisher.cpp.


Member Function Documentation

Definition at line 161 of file movement_publisher.cpp.

Used to listen to a sr_robot_msgs::JointControllerState and calculate the mean square error of every movement repetition

the current state of the controller.

Definition at line 111 of file movement_publisher.cpp.

void shadowrobot::MovementPublisher::execute_step ( int  index_mvt_step,
int  index_partial_movement 
)

Allows the user to control the movement step by step.

Definition at line 135 of file movement_publisher.cpp.

Used to listen to a pr2_controller_msgs::JointControllerState and calculate the mean square error of every movement repetition

the current state of the controller.

Definition at line 123 of file movement_publisher.cpp.

Definition at line 166 of file movement_publisher.cpp.

Definition at line 61 of file movement_publisher.cpp.

Definition at line 158 of file movement_publisher.cpp.


Member Data Documentation

Definition at line 95 of file movement_publisher.hpp.

Definition at line 89 of file movement_publisher.hpp.

Definition at line 86 of file movement_publisher.hpp.

Definition at line 86 of file movement_publisher.hpp.

Definition at line 93 of file movement_publisher.hpp.

Definition at line 88 of file movement_publisher.hpp.

Definition at line 94 of file movement_publisher.hpp.

Definition at line 91 of file movement_publisher.hpp.

Definition at line 79 of file movement_publisher.hpp.

Definition at line 78 of file movement_publisher.hpp.

Definition at line 80 of file movement_publisher.hpp.

Definition at line 81 of file movement_publisher.hpp.

Definition at line 84 of file movement_publisher.hpp.

Definition at line 85 of file movement_publisher.hpp.

Definition at line 92 of file movement_publisher.hpp.

Definition at line 82 of file movement_publisher.hpp.


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


sr_movements
Author(s): Ugo Cupcic / ugo@shadowrobot.com
autogenerated on Fri Jan 3 2014 12:08:55