#include <movement_publisher.hpp>
|
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 () |
|
Definition at line 44 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.
- Parameters
-
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 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 = "" |
|
) |
| |
shadowrobot::MovementPublisher::~MovementPublisher |
( |
| ) |
|
|
virtual |
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
-
msg | the 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 |
|
) |
| |
std::string shadowrobot::MovementPublisher::get_subscriber_topic |
( |
| ) |
|
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 | ) |
|
void shadowrobot::MovementPublisher::set_subscriber |
( |
ros::Subscriber |
subscriber | ) |
|
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
-
msg | the current state of the controller. |
Definition at line 151 of file movement_publisher.cpp.
void shadowrobot::MovementPublisher::start |
( |
| ) |
|
void shadowrobot::MovementPublisher::stop |
( |
| ) |
|
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
-
input | Topic to which we're subscribing. |
Definition at line 82 of file movement_publisher.cpp.
std::string shadowrobot::MovementPublisher::controller_type |
|
protected |
std::string shadowrobot::MovementPublisher::joint_name_ |
|
protected |
std::vector<sr_robot_msgs::joint> shadowrobot::MovementPublisher::joint_vector_ |
|
protected |
double shadowrobot::MovementPublisher::last_target_ |
|
protected |
double shadowrobot::MovementPublisher::max |
|
protected |
double shadowrobot::MovementPublisher::min |
|
protected |
double shadowrobot::MovementPublisher::MSError_ |
|
protected |
std_msgs::Float64 shadowrobot::MovementPublisher::msg |
|
protected |
unsigned int shadowrobot::MovementPublisher::n_samples_ |
|
protected |
unsigned int shadowrobot::MovementPublisher::nb_mvt_step |
|
protected |
std::vector<PartialMovement> shadowrobot::MovementPublisher::partial_movements |
|
protected |
ros::Rate shadowrobot::MovementPublisher::publishing_rate |
|
protected |
unsigned int shadowrobot::MovementPublisher::repetition |
|
protected |
double shadowrobot::MovementPublisher::SError_ |
|
protected |
The documentation for this class was generated from the following files: