A simple interface that adds an interactive marker (to be used in rviz
) with two controls to change respectively the shaft position and the stiffness of a qbmove device.
More...
#include <qb_move_interactive_interface.h>
|
void | buildCylinder (visualization_msgs::InteractiveMarker &interactive_marker) |
| Create a cylinder marker representing the qbmove shaft axis and attach it to the given interactive marker. More...
|
|
void | buildMotorControl (visualization_msgs::InteractiveMarker &interactive_marker) |
| Add two interactive controls to the given interactive marker. More...
|
|
double | computeAngularDistance (const geometry_msgs::Quaternion &to_pose, const geometry_msgs::Quaternion &from_pose) |
| Compute the angular distance between current and last orientations. More...
|
|
trajectory_msgs::JointTrajectory | computeJointTrajectories (const double &displacement_position, const double &displacement_stiffness) |
| Compute a simple joint trajectory from the given displacements in position and orientation. More...
|
|
double | computeLinearDistance (const geometry_msgs::Point &to_pose, const geometry_msgs::Point &from_pose) |
| Compute the distance along the marker axis between current and last positions. More...
|
|
double | getStiffnessFromScale () |
|
void | interactiveMarkerCallback (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) |
| This is the core method of the class, where commands are computed w.r.t. More...
|
|
void | setScaleFromStiffness (const double &stiffness_value) |
| Set the diameter scale of the marker from the given stiffness value. More...
|
|
A simple interface that adds an interactive marker (to be used in rviz
) with two controls to change respectively the shaft position and the stiffness of a qbmove device.
The core features are called in the server callback where feedback from the marker are handled.
- See also
- interactiveMarkerCallback()
Definition at line 43 of file qb_move_interactive_interface.h.
qb_move_interactive_interface::qbMoveInteractive::qbMoveInteractive |
( |
| ) |
|
|
inline |
virtual qb_move_interactive_interface::qbMoveInteractive::~qbMoveInteractive |
( |
| ) |
|
|
inlinevirtual |
void qb_move_interactive_interface::qbMoveInteractive::buildCylinder |
( |
visualization_msgs::InteractiveMarker & |
interactive_marker | ) |
|
|
inlineprotected |
Create a cylinder marker representing the qbmove shaft axis and attach it to the given interactive marker.
- Parameters
-
interactive_marker | The Interactive Marker structure to be filled. |
Definition at line 128 of file qb_move_interactive_interface.h.
void qb_move_interactive_interface::qbMoveInteractive::buildMotorControl |
( |
visualization_msgs::InteractiveMarker & |
interactive_marker | ) |
|
|
inlineprotected |
Add two interactive controls to the given interactive marker.
The first let to rotate the shaft, while the second allow to change the device stiffness. The change in shaft position is clear from the orientation of the flange attached to the qbmove; on the other hand a change in stiffness is represented graphically with a bigger or smaller cylinder, respectively for more and less stiffness.
- Parameters
-
interactive_marker | The Interactive Marker structure to be filled. |
Definition at line 158 of file qb_move_interactive_interface.h.
double qb_move_interactive_interface::qbMoveInteractive::computeAngularDistance |
( |
const geometry_msgs::Quaternion & |
to_pose, |
|
|
const geometry_msgs::Quaternion & |
from_pose |
|
) |
| |
|
inlineprotected |
Compute the angular distance between current and last orientations.
- Parameters
-
to_pose | The current orientation of the marker. |
from_pose | The last known orientation of the marker. |
- Returns
- The computed angular distance.
Definition at line 180 of file qb_move_interactive_interface.h.
trajectory_msgs::JointTrajectory qb_move_interactive_interface::qbMoveInteractive::computeJointTrajectories |
( |
const double & |
displacement_position, |
|
|
const double & |
displacement_stiffness |
|
) |
| |
|
inlineprotected |
Compute a simple joint trajectory from the given displacements in position and orientation.
- Parameters
-
displacement_position | The displacement in angular position of the shaft, expressed in radians. |
displacement_stiffness | The displacement in stiffness of the device, expressed in [0,1]; |
- Returns
- The joint trajectory filled with the proper commands.
Definition at line 208 of file qb_move_interactive_interface.h.
Compute the distance along the marker axis between current and last positions.
- Parameters
-
to_pose | The current position of the marker. |
from_pose | The last known position of the marker. |
- Returns
- The computed distance.
Definition at line 198 of file qb_move_interactive_interface.h.
double qb_move_interactive_interface::qbMoveInteractive::getStiffnessFromScale |
( |
| ) |
|
|
inlineprotected |
void qb_move_interactive_interface::qbMoveInteractive::initMarkers |
( |
ros::NodeHandle & |
root_nh, |
|
|
const std::string & |
device_name, |
|
|
const std::vector< std::string > & |
joint_names |
|
) |
| |
|
inline |
void qb_move_interactive_interface::qbMoveInteractive::interactiveMarkerCallback |
( |
const visualization_msgs::InteractiveMarkerFeedbackConstPtr & |
feedback | ) |
|
|
inlineprotected |
This is the core method of the class, where commands are computed w.r.t.
the previous state of the interactive marker and the computed joint trajectory is sent to the low level controller, e.g. the joint trajectory controller of the qbMoveHW
.
- Parameters
-
feedback | The feedback state of the interactive marker, provided by rviz. |
Definition at line 238 of file qb_move_interactive_interface.h.
void qb_move_interactive_interface::qbMoveInteractive::setMarkerState |
( |
const std::vector< double > & |
joint_positions | ) |
|
|
inline |
Update the stored joint positions with the given values.
It is aimed to be called when reading HW.
- Parameters
-
joint_positions | The vector of the actuated joint positions, basically [shaft_position, stiffness]. |
Definition at line 105 of file qb_move_interactive_interface.h.
void qb_move_interactive_interface::qbMoveInteractive::setScaleFromStiffness |
( |
const double & |
stiffness_value | ) |
|
|
inlineprotected |
visualization_msgs::InteractiveMarker qb_move_interactive_interface::qbMoveInteractive::controls_ |
|
protected |
visualization_msgs::InteractiveMarker qb_move_interactive_interface::qbMoveInteractive::cylinder_ |
|
protected |
std::string qb_move_interactive_interface::qbMoveInteractive::device_name_ |
|
protected |
ros::Publisher qb_move_interactive_interface::qbMoveInteractive::joint_command_pub_ |
|
protected |
trajectory_msgs::JointTrajectory qb_move_interactive_interface::qbMoveInteractive::joint_command_trajectories_ |
|
protected |
std::vector<std::string> qb_move_interactive_interface::qbMoveInteractive::joint_names_ |
|
protected |
std::vector<double> qb_move_interactive_interface::qbMoveInteractive::joint_positions_ |
|
protected |
The documentation for this class was generated from the following file: