#include <joint_spline_trajectory_action_controller.hpp>
|
static void | sampleSplineWithTimeBounds (const std::vector< double > &coefficients, double duration, double time, double &position, double &velocity, double &acceleration) |
|
◆ JointPubMap
◆ JointTrajectoryPointVec
◆ JTAS [1/2]
◆ JTAS [2/2]
◆ SpecifiedTrajectory
◆ JointTrajectoryActionController() [1/2]
shadowrobot::JointTrajectoryActionController::JointTrajectoryActionController |
( |
| ) |
|
◆ JointTrajectoryActionController() [2/2]
shadowrobot::JointTrajectoryActionController::JointTrajectoryActionController |
( |
| ) |
|
◆ commandCB()
void shadowrobot::JointTrajectoryActionController::commandCB |
( |
const trajectory_msgs::JointTrajectoryConstPtr & |
msg | ) |
|
|
private |
◆ execute_trajectory() [1/2]
void shadowrobot::JointTrajectoryActionController::execute_trajectory |
( |
const control_msgs::FollowJointTrajectoryGoalConstPtr & |
goal | ) |
|
|
private |
◆ execute_trajectory() [2/2]
void shadowrobot::JointTrajectoryActionController::execute_trajectory |
( |
const control_msgs::FollowJointTrajectoryGoalConstPtr & |
goal | ) |
|
|
private |
◆ getPosition()
bool shadowrobot::JointTrajectoryActionController::getPosition |
( |
std::string |
joint_name, |
|
|
double & |
position |
|
) |
| |
|
private |
◆ sampleSplineWithTimeBounds()
void shadowrobot::JointTrajectoryActionController::sampleSplineWithTimeBounds |
( |
const std::vector< double > & |
coefficients, |
|
|
double |
duration, |
|
|
double |
time, |
|
|
double & |
position, |
|
|
double & |
velocity, |
|
|
double & |
acceleration |
|
) |
| |
|
staticprivate |
◆ updateJointState()
void shadowrobot::JointTrajectoryActionController::updateJointState |
( |
| ) |
|
|
private |
◆ action_server
◆ command_sub
◆ controller_publishers
std::vector<ros::Publisher> shadowrobot::JointTrajectoryActionController::controller_publishers |
|
private |
◆ desired_joint_state_pusblisher
ros::Publisher shadowrobot::JointTrajectoryActionController::desired_joint_state_pusblisher |
|
private |
◆ joint_names_
std::vector<std::string> shadowrobot::JointTrajectoryActionController::joint_names_ |
|
private |
◆ joint_pub
JointPubMap shadowrobot::JointTrajectoryActionController::joint_pub |
|
private |
◆ joint_state_client
◆ joint_state_idx_map
std::map<std::string, unsigned int> shadowrobot::JointTrajectoryActionController::joint_state_idx_map |
|
private |
◆ joint_state_map
std::map<std::string, double> shadowrobot::JointTrajectoryActionController::joint_state_map |
|
private |
◆ jointControllerMap
std::map<std::string, std::string> shadowrobot::JointTrajectoryActionController::jointControllerMap |
|
private |
◆ jointPubIdxMap
std::map<std::string, unsigned int> shadowrobot::JointTrajectoryActionController::jointPubIdxMap |
|
private |
◆ last_time_
ros::Time shadowrobot::JointTrajectoryActionController::last_time_ |
|
private |
◆ nh
◆ nh_tilde
std::vector<double> shadowrobot::JointTrajectoryActionController::q |
|
private |
◆ qd
std::vector<double> shadowrobot::JointTrajectoryActionController::qd |
|
private |
◆ qdd
std::vector<double> shadowrobot::JointTrajectoryActionController::qdd |
|
private |
◆ sr_arm_target_pub
ros::Publisher shadowrobot::JointTrajectoryActionController::sr_arm_target_pub |
|
private |
◆ sr_hand_target_pub
ros::Publisher shadowrobot::JointTrajectoryActionController::sr_hand_target_pub |
|
private |
◆ use_sendupdate
bool shadowrobot::JointTrajectoryActionController::use_sendupdate |
|
private |
The documentation for this class was generated from the following files: