Public Member Functions | Protected 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)
std::string get_subscriber_topic ()
 MovementPublisher (std::string joint_name, double rate=100.0, unsigned int repetition=1, unsigned int nb_mvt_step=1000, std::string controller_type="", bool testing=false, HandCommander *hand_commander=NULL)
 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 set_subscriber (ros::Subscriber subscriber)
void start ()
void stop ()
virtual ~MovementPublisher ()

Protected Member Functions

void publish_ ()
void subscribe_and_default_pub_ (std::string input)

Protected Attributes

std::string controller_type
boost::shared_ptr< HandCommanderhand_commander_
std::string joint_name_
std::vector< sr_robot_msgs::joint > joint_vector_
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_mse_
ros::Rate publishing_rate
unsigned int repetition
double SError_
ros::Subscriber sub_

Detailed Description

Definition at line 42 of file movement_publisher.hpp.


Constructor & Destructor Documentation

shadowrobot::MovementPublisher::MovementPublisher ( std::string  joint_name,
double  rate = 100.0,
unsigned int  repetition = 1,
unsigned int  nb_mvt_step = 1000,
std::string  controller_type = "",
bool  testing = false,
HandCommander hand_commander = NULL 
)

This is the constructor used when providing a joint name. It automatically extracts the min and max + subscriber / publishers from the HandCommander.

Parameters:
joint_namethe name of the joint we want to move.
raterate at which the targets should be published.
repetitionnumber of times the movement should be repeated
nb_mvt_stepnumber of steps we take in the image
controller_typethe type of controller ("sr" or "pr2")
testingset to true when running a gazebo test (just adds a long sleep).
hand_commanderhelper for controlling the shadow hand

Definition at line 33 of file movement_publisher.cpp.

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 64 of file movement_publisher.cpp.

Definition at line 97 of file movement_publisher.cpp.


Member Function Documentation

Definition at line 214 of file movement_publisher.cpp.

void shadowrobot::MovementPublisher::calculateErrorCallback ( const sr_robot_msgs::JointControllerState::ConstPtr &  msg)

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

Parameters:
msgthe current state of the controller.

Definition at line 150 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 174 of file movement_publisher.cpp.

Definition at line 229 of file movement_publisher.cpp.

void shadowrobot::MovementPublisher::pr2_calculateErrorCallback ( const pr2_controllers_msgs::JointControllerState::ConstPtr &  msg)

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

Parameters:
msgthe current state of the controller.

Definition at line 162 of file movement_publisher.cpp.

Publishes the message, using either the HandCommander (recommended) or the previous approach, using directly a remapped publisher.

Definition at line 196 of file movement_publisher.cpp.

Definition at line 219 of file movement_publisher.cpp.

Definition at line 224 of file movement_publisher.cpp.

Definition at line 100 of file movement_publisher.cpp.

Definition at line 211 of file movement_publisher.cpp.

void shadowrobot::MovementPublisher::subscribe_and_default_pub_ ( std::string  input) [protected]

Subscribes with the correct type (based on controller_type_) to the given topic. Also initialises the MSE publisher.

Parameters:
inputTopic to which we're subscribing.

Definition at line 76 of file movement_publisher.cpp.


Member Data Documentation

Definition at line 139 of file movement_publisher.hpp.

Definition at line 118 of file movement_publisher.hpp.

Definition at line 119 of file movement_publisher.hpp.

std::vector<sr_robot_msgs::joint> shadowrobot::MovementPublisher::joint_vector_ [protected]

Definition at line 132 of file movement_publisher.hpp.

Definition at line 133 of file movement_publisher.hpp.

Definition at line 129 of file movement_publisher.hpp.

Definition at line 129 of file movement_publisher.hpp.

Definition at line 137 of file movement_publisher.hpp.

std_msgs::Float64 shadowrobot::MovementPublisher::msg [protected]

Definition at line 131 of file movement_publisher.hpp.

Definition at line 138 of file movement_publisher.hpp.

Definition at line 135 of file movement_publisher.hpp.

Definition at line 122 of file movement_publisher.hpp.

Definition at line 121 of file movement_publisher.hpp.

Definition at line 123 of file movement_publisher.hpp.

Definition at line 124 of file movement_publisher.hpp.

Definition at line 127 of file movement_publisher.hpp.

Definition at line 128 of file movement_publisher.hpp.

Definition at line 136 of file movement_publisher.hpp.

Definition at line 125 of file movement_publisher.hpp.


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


sr_movements
Author(s): Ugo Cupcic
autogenerated on Fri Aug 28 2015 13:09:30