#include <arm_controller.h>
Definition at line 64 of file arm_controller.h.
ArmController::ArmController |
( |
| ) |
|
ArmController::~ArmController |
( |
| ) |
|
|
virtual |
bool ArmController::calcPlannedPath |
( |
open_manipulator_msgs::JointPosition |
msg | ) |
|
|
private |
bool ArmController::calcPlannedPath |
( |
open_manipulator_msgs::KinematicsPose |
msg | ) |
|
|
private |
void ArmController::displayPlannedPathMsgCallback |
( |
const moveit_msgs::DisplayTrajectory::ConstPtr & |
msg | ) |
|
|
private |
bool ArmController::getJointPositionMsgCallback |
( |
open_manipulator_msgs::GetJointPosition::Request & |
req, |
|
|
open_manipulator_msgs::GetJointPosition::Response & |
res |
|
) |
| |
|
private |
bool ArmController::getKinematicsPoseMsgCallback |
( |
open_manipulator_msgs::GetKinematicsPose::Request & |
req, |
|
|
open_manipulator_msgs::GetKinematicsPose::Response & |
res |
|
) |
| |
|
private |
void ArmController::initJointPosition |
( |
| ) |
|
|
private |
void ArmController::initPublisher |
( |
bool |
using_gazebo | ) |
|
|
private |
void ArmController::initServer |
( |
| ) |
|
|
private |
void ArmController::initSubscriber |
( |
bool |
using_gazebo | ) |
|
|
private |
void ArmController::process |
( |
void |
| ) |
|
bool ArmController::setJointPositionMsgCallback |
( |
open_manipulator_msgs::SetJointPosition::Request & |
req, |
|
|
open_manipulator_msgs::SetJointPosition::Response & |
res |
|
) |
| |
|
private |
bool ArmController::setKinematicsPoseMsgCallback |
( |
open_manipulator_msgs::SetKinematicsPose::Request & |
req, |
|
|
open_manipulator_msgs::SetKinematicsPose::Response & |
res |
|
) |
| |
|
private |
uint16_t open_manipulator::ArmController::all_time_steps_ |
|
private |
ros::Publisher open_manipulator::ArmController::gazebo_goal_joint_position_pub_[10] |
|
private |
ros::Publisher open_manipulator::ArmController::goal_joint_position_pub_ |
|
private |
bool open_manipulator::ArmController::init_position_ |
|
private |
bool open_manipulator::ArmController::is_moving_ |
|
private |
int open_manipulator::ArmController::joint_num_ |
|
private |
std::string open_manipulator::ArmController::robot_name_ |
|
private |
bool open_manipulator::ArmController::using_gazebo_ |
|
private |
The documentation for this class was generated from the following files: