#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< PartialMovement > | partial_movements |
ros::Publisher | pub |
ros::Publisher | pub_mse_ |
ros::Rate | publishing_rate |
unsigned int | repetition |
double | SError_ |
ros::Subscriber | sub_ |
Definition at line 42 of file movement_publisher.hpp.
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.
joint_name | the name of the joint we want to move. |
rate | rate at which the targets should be published. |
repetition | number of times the movement should be repeated |
nb_mvt_step | number of steps we take in the image |
controller_type | the type of controller ("sr" or "ros") |
testing | set to true when running a gazebo test (just adds a long sleep). |
hand_commander | helper 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.
shadowrobot::MovementPublisher::~MovementPublisher | ( | ) | [virtual] |
Definition at line 92 of file movement_publisher.cpp.
Definition at line 209 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
msg | the current state of the controller. |
Definition at line 157 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 169 of file movement_publisher.cpp.
Definition at line 224 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 191 of file movement_publisher.cpp.
void shadowrobot::MovementPublisher::set_publisher | ( | ros::Publisher | publisher | ) |
Definition at line 214 of file movement_publisher.cpp.
void shadowrobot::MovementPublisher::set_subscriber | ( | ros::Subscriber | subscriber | ) |
Definition at line 219 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
msg | the current state of the controller. |
Definition at line 145 of file movement_publisher.cpp.
void shadowrobot::MovementPublisher::start | ( | void | ) |
Definition at line 95 of file movement_publisher.cpp.
void shadowrobot::MovementPublisher::stop | ( | void | ) |
Definition at line 206 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.
input | Topic to which we're subscribing. |
Definition at line 76 of file movement_publisher.cpp.
Definition at line 139 of file movement_publisher.hpp.
boost::shared_ptr<HandCommander> shadowrobot::MovementPublisher::hand_commander_ [protected] |
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.
double shadowrobot::MovementPublisher::last_target_ [protected] |
Definition at line 133 of file movement_publisher.hpp.
double shadowrobot::MovementPublisher::max [protected] |
Definition at line 129 of file movement_publisher.hpp.
double shadowrobot::MovementPublisher::min [protected] |
Definition at line 129 of file movement_publisher.hpp.
double shadowrobot::MovementPublisher::MSError_ [protected] |
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.
unsigned int shadowrobot::MovementPublisher::n_samples_ [protected] |
Definition at line 138 of file movement_publisher.hpp.
unsigned int shadowrobot::MovementPublisher::nb_mvt_step [protected] |
Definition at line 135 of file movement_publisher.hpp.
Definition at line 122 of file movement_publisher.hpp.
std::vector<PartialMovement> shadowrobot::MovementPublisher::partial_movements [protected] |
Definition at line 121 of file movement_publisher.hpp.
ros::Publisher shadowrobot::MovementPublisher::pub [protected] |
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.
unsigned int shadowrobot::MovementPublisher::repetition [protected] |
Definition at line 128 of file movement_publisher.hpp.
double shadowrobot::MovementPublisher::SError_ [protected] |
Definition at line 136 of file movement_publisher.hpp.
ros::Subscriber shadowrobot::MovementPublisher::sub_ [protected] |
Definition at line 125 of file movement_publisher.hpp.