Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
shadowrobot::MovementPublisher Class Reference

#include <movement_publisher.hpp>

Public Member Functions

void add_movement (PartialMovement mvt)
 
void calculateErrorCallback (const control_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 set_publisher (ros::Publisher publisher)
 
void set_subscriber (ros::Subscriber subscriber)
 
void sr_calculateErrorCallback (const sr_robot_msgs::JointControllerState::ConstPtr &msg)
 
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< HandCommander > hand_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 44 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 "ros")
testingset to true when running a gazebo test (just adds a long sleep).
hand_commanderhelper for controlling the shadow hand

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

shadowrobot::MovementPublisher::~MovementPublisher ( )
virtual

Definition at line 98 of file movement_publisher.cpp.

Member Function Documentation

void shadowrobot::MovementPublisher::add_movement ( PartialMovement  mvt)

Definition at line 216 of file movement_publisher.cpp.

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

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

Parameters
msgthe current state of the controller.

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

std::string shadowrobot::MovementPublisher::get_subscriber_topic ( )

Definition at line 231 of file movement_publisher.cpp.

void shadowrobot::MovementPublisher::publish_ ( )
protected

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

Definition at line 198 of file movement_publisher.cpp.

void shadowrobot::MovementPublisher::set_publisher ( ros::Publisher  publisher)

Definition at line 221 of file movement_publisher.cpp.

void shadowrobot::MovementPublisher::set_subscriber ( ros::Subscriber  subscriber)

Definition at line 226 of file movement_publisher.cpp.

void shadowrobot::MovementPublisher::sr_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 151 of file movement_publisher.cpp.

void shadowrobot::MovementPublisher::start ( )

Definition at line 101 of file movement_publisher.cpp.

void shadowrobot::MovementPublisher::stop ( )

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

Member Data Documentation

std::string shadowrobot::MovementPublisher::controller_type
protected

Definition at line 141 of file movement_publisher.hpp.

boost::shared_ptr<HandCommander> shadowrobot::MovementPublisher::hand_commander_
protected

Definition at line 120 of file movement_publisher.hpp.

std::string shadowrobot::MovementPublisher::joint_name_
protected

Definition at line 121 of file movement_publisher.hpp.

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

Definition at line 134 of file movement_publisher.hpp.

double shadowrobot::MovementPublisher::last_target_
protected

Definition at line 135 of file movement_publisher.hpp.

double shadowrobot::MovementPublisher::max
protected

Definition at line 131 of file movement_publisher.hpp.

double shadowrobot::MovementPublisher::min
protected

Definition at line 131 of file movement_publisher.hpp.

double shadowrobot::MovementPublisher::MSError_
protected

Definition at line 139 of file movement_publisher.hpp.

std_msgs::Float64 shadowrobot::MovementPublisher::msg
protected

Definition at line 133 of file movement_publisher.hpp.

unsigned int shadowrobot::MovementPublisher::n_samples_
protected

Definition at line 140 of file movement_publisher.hpp.

unsigned int shadowrobot::MovementPublisher::nb_mvt_step
protected

Definition at line 137 of file movement_publisher.hpp.

ros::NodeHandle shadowrobot::MovementPublisher::nh_tilde
protected

Definition at line 124 of file movement_publisher.hpp.

std::vector<PartialMovement> shadowrobot::MovementPublisher::partial_movements
protected

Definition at line 123 of file movement_publisher.hpp.

ros::Publisher shadowrobot::MovementPublisher::pub
protected

Definition at line 125 of file movement_publisher.hpp.

ros::Publisher shadowrobot::MovementPublisher::pub_mse_
protected

Definition at line 126 of file movement_publisher.hpp.

ros::Rate shadowrobot::MovementPublisher::publishing_rate
protected

Definition at line 129 of file movement_publisher.hpp.

unsigned int shadowrobot::MovementPublisher::repetition
protected

Definition at line 130 of file movement_publisher.hpp.

double shadowrobot::MovementPublisher::SError_
protected

Definition at line 138 of file movement_publisher.hpp.

ros::Subscriber shadowrobot::MovementPublisher::sub_
protected

Definition at line 127 of file movement_publisher.hpp.


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


sr_movements
Author(s): Ugo Cupcic
autogenerated on Tue Oct 13 2020 03:50:46