Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
qb_move_interactive_interface::qbMoveInteractive Class Reference

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>

Public Member Functions

void initMarkers (ros::NodeHandle &root_nh, const std::string &device_name, const std::vector< std::string > &joint_names)
 Initialize the interactive_markers::InteractiveMarkerServer and the marker displayed in rviz to control the shaft position of the qbmove device and its stiffness. More...
 
 qbMoveInteractive ()
 Start the async spinner and do nothing else. More...
 
void setMarkerState (const std::vector< double > &joint_positions)
 Update the stored joint positions with the given values. More...
 
virtual ~qbMoveInteractive ()
 Stop the async spinner. More...
 

Protected Member Functions

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...
 

Protected Attributes

visualization_msgs::InteractiveMarker controls_
 
geometry_msgs::Pose controls_position_old_
 
geometry_msgs::Pose controls_position_orig_
 
visualization_msgs::InteractiveMarker cylinder_
 
std::string device_name_
 
std::unique_ptr< interactive_markers::InteractiveMarkerServerinteractive_commands_server_
 
ros::Publisher joint_command_pub_
 
trajectory_msgs::JointTrajectory joint_command_trajectories_
 
std::vector< std::string > joint_names_
 
std::vector< double > joint_positions_
 
ros::AsyncSpinner spinner_
 

Detailed Description

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.

Constructor & Destructor Documentation

qb_move_interactive_interface::qbMoveInteractive::qbMoveInteractive ( )
inline

Start the async spinner and do nothing else.

The real initialization is done later by initMarkers().

See also
initMarkers()

Definition at line 49 of file qb_move_interactive_interface.h.

virtual qb_move_interactive_interface::qbMoveInteractive::~qbMoveInteractive ( )
inlinevirtual

Stop the async spinner.

Definition at line 57 of file qb_move_interactive_interface.h.

Member Function Documentation

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_markerThe 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_markerThe 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_poseThe current orientation of the marker.
from_poseThe 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_positionThe displacement in angular position of the shaft, expressed in radians.
displacement_stiffnessThe 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.

double qb_move_interactive_interface::qbMoveInteractive::computeLinearDistance ( const geometry_msgs::Point to_pose,
const geometry_msgs::Point from_pose 
)
inlineprotected

Compute the distance along the marker axis between current and last positions.

Parameters
to_poseThe current position of the marker.
from_poseThe 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
Returns
The stiffness value computed by the diameter scale of the marker.
See also
setScaleFromStiffness()

Definition at line 228 of file qb_move_interactive_interface.h.

void qb_move_interactive_interface::qbMoveInteractive::initMarkers ( ros::NodeHandle root_nh,
const std::string &  device_name,
const std::vector< std::string > &  joint_names 
)
inline

Initialize the interactive_markers::InteractiveMarkerServer and the marker displayed in rviz to control the shaft position of the qbmove device and its stiffness.

This method is called by the qbMoveHW during its initialization.

Parameters
root_nhA NodeHandle in the root of the caller namespace (depends from the one in the hardware interface).
device_nameThe unique device name.
joint_namesThe vector of the actuated joint names.
See also
buildCylinder(), buildMotorControl()

Definition at line 70 of file qb_move_interactive_interface.h.

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
feedbackThe 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_positionsThe 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

Set the diameter scale of the marker from the given stiffness value.

Parameters
stiffness_valueThe qbmove stiffness value.
See also
getStiffnessFromScale()

Definition at line 277 of file qb_move_interactive_interface.h.

Member Data Documentation

visualization_msgs::InteractiveMarker qb_move_interactive_interface::qbMoveInteractive::controls_
protected

Definition at line 120 of file qb_move_interactive_interface.h.

geometry_msgs::Pose qb_move_interactive_interface::qbMoveInteractive::controls_position_old_
protected

Definition at line 121 of file qb_move_interactive_interface.h.

geometry_msgs::Pose qb_move_interactive_interface::qbMoveInteractive::controls_position_orig_
protected

Definition at line 122 of file qb_move_interactive_interface.h.

visualization_msgs::InteractiveMarker qb_move_interactive_interface::qbMoveInteractive::cylinder_
protected

Definition at line 119 of file qb_move_interactive_interface.h.

std::string qb_move_interactive_interface::qbMoveInteractive::device_name_
protected

Definition at line 116 of file qb_move_interactive_interface.h.

std::unique_ptr<interactive_markers::InteractiveMarkerServer> qb_move_interactive_interface::qbMoveInteractive::interactive_commands_server_
protected

Definition at line 118 of file qb_move_interactive_interface.h.

ros::Publisher qb_move_interactive_interface::qbMoveInteractive::joint_command_pub_
protected

Definition at line 112 of file qb_move_interactive_interface.h.

trajectory_msgs::JointTrajectory qb_move_interactive_interface::qbMoveInteractive::joint_command_trajectories_
protected

Definition at line 113 of file qb_move_interactive_interface.h.

std::vector<std::string> qb_move_interactive_interface::qbMoveInteractive::joint_names_
protected

Definition at line 114 of file qb_move_interactive_interface.h.

std::vector<double> qb_move_interactive_interface::qbMoveInteractive::joint_positions_
protected

Definition at line 115 of file qb_move_interactive_interface.h.

ros::AsyncSpinner qb_move_interactive_interface::qbMoveInteractive::spinner_
protected

Definition at line 111 of file qb_move_interactive_interface.h.


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


qb_move_hardware_interface
Author(s): qbroboticsĀ®
autogenerated on Wed Jun 12 2019 19:18:54