#include <jog_api.h>
|
bool | jacobianMove (geometry_msgs::PoseStamped &target_pose, const double trans_tolerance, const double rot_tolerance, const std::vector< double > &speed_scale, const ros::Duration &timeout) |
|
| JogAPI (const std::string &move_group_name, const std::string &outgoing_jog_topic) |
|
bool | maintainPose (std::string frame, const ros::Duration duration, const std::vector< double > &speed_scale) |
|
Definition at line 43 of file jog_api.h.
JogAPI::JogAPI |
( |
const std::string & |
move_group_name, |
|
|
const std::string & |
outgoing_jog_topic |
|
) |
| |
|
inline |
JogAPI::distanceAndTwist JogAPI::calculateDistanceAndTwist |
( |
const geometry_msgs::PoseStamped & |
current_pose, |
|
|
const geometry_msgs::PoseStamped & |
target_pose, |
|
|
const std::vector< double > & |
speed_scale |
|
) |
| |
|
private |
bool JogAPI::jacobianMove |
( |
geometry_msgs::PoseStamped & |
target_pose, |
|
|
const double |
trans_tolerance, |
|
|
const double |
rot_tolerance, |
|
|
const std::vector< double > & |
speed_scale, |
|
|
const ros::Duration & |
timeout |
|
) |
| |
bool JogAPI::maintainPose |
( |
std::string |
frame, |
|
|
const ros::Duration |
duration, |
|
|
const std::vector< double > & |
speed_scale |
|
) |
| |
bool JogAPI::transformPose |
( |
geometry_msgs::PoseStamped & |
pose, |
|
|
std::string & |
desired_frame |
|
) |
| |
|
private |
The documentation for this class was generated from the following files: