Public Member Functions | Private Member Functions | Private Attributes | List of all members
open_manipulator::ArmController Class Reference

#include <arm_controller.h>

Public Member Functions

 ArmController ()
 
void process (void)
 
virtual ~ArmController ()
 

Private Member Functions

bool calcPlannedPath (open_manipulator_msgs::JointPosition msg)
 
bool calcPlannedPath (open_manipulator_msgs::KinematicsPose msg)
 
void displayPlannedPathMsgCallback (const moveit_msgs::DisplayTrajectory::ConstPtr &msg)
 
bool getJointPositionMsgCallback (open_manipulator_msgs::GetJointPosition::Request &req, open_manipulator_msgs::GetJointPosition::Response &res)
 
bool getKinematicsPoseMsgCallback (open_manipulator_msgs::GetKinematicsPose::Request &req, open_manipulator_msgs::GetKinematicsPose::Response &res)
 
void initJointPosition ()
 
void initPublisher (bool using_gazebo)
 
void initServer ()
 
void initSubscriber (bool using_gazebo)
 
bool setJointPositionMsgCallback (open_manipulator_msgs::SetJointPosition::Request &req, open_manipulator_msgs::SetJointPosition::Response &res)
 
bool setKinematicsPoseMsgCallback (open_manipulator_msgs::SetKinematicsPose::Request &req, open_manipulator_msgs::SetKinematicsPose::Response &res)
 

Private Attributes

uint16_t all_time_steps_
 
ros::Publisher arm_state_pub_
 
ros::Subscriber display_planned_path_sub_
 
ros::Publisher gazebo_goal_joint_position_pub_ [10]
 
ros::ServiceServer get_joint_position_server_
 
ros::ServiceServer get_kinematics_pose_server_
 
ros::Publisher goal_joint_position_pub_
 
bool init_position_
 
bool is_moving_
 
int joint_num_
 
moveit::planning_interface::MoveGroupInterfacemove_group
 
ros::NodeHandle nh_
 
PlannedPathInfo planned_path_info_
 
ros::NodeHandle priv_nh_
 
std::string robot_name_
 
ros::ServiceServer set_joint_position_server_
 
ros::ServiceServer set_kinematics_pose_server_
 
bool using_gazebo_
 

Detailed Description

Definition at line 64 of file arm_controller.h.

Constructor & Destructor Documentation

ArmController::ArmController ( )

Definition at line 23 of file arm_controller.cpp.

ArmController::~ArmController ( )
virtual

Definition at line 52 of file arm_controller.cpp.

Member Function Documentation

bool ArmController::calcPlannedPath ( open_manipulator_msgs::JointPosition  msg)
private

Definition at line 216 of file arm_controller.cpp.

bool ArmController::calcPlannedPath ( open_manipulator_msgs::KinematicsPose  msg)
private

Definition at line 174 of file arm_controller.cpp.

void ArmController::displayPlannedPathMsgCallback ( const moveit_msgs::DisplayTrajectory::ConstPtr &  msg)
private

Definition at line 270 of file arm_controller.cpp.

bool ArmController::getJointPositionMsgCallback ( open_manipulator_msgs::GetJointPosition::Request &  req,
open_manipulator_msgs::GetJointPosition::Response &  res 
)
private

Definition at line 122 of file arm_controller.cpp.

bool ArmController::getKinematicsPoseMsgCallback ( open_manipulator_msgs::GetKinematicsPose::Request &  req,
open_manipulator_msgs::GetKinematicsPose::Response &  res 
)
private

Definition at line 142 of file arm_controller.cpp.

void ArmController::initJointPosition ( )
private

Definition at line 58 of file arm_controller.cpp.

void ArmController::initPublisher ( bool  using_gazebo)
private

Definition at line 78 of file arm_controller.cpp.

void ArmController::initServer ( )
private

Definition at line 114 of file arm_controller.cpp.

void ArmController::initSubscriber ( bool  using_gazebo)
private

Definition at line 108 of file arm_controller.cpp.

void ArmController::process ( void  )

Definition at line 301 of file arm_controller.cpp.

bool ArmController::setJointPositionMsgCallback ( open_manipulator_msgs::SetJointPosition::Request &  req,
open_manipulator_msgs::SetJointPosition::Response &  res 
)
private

Definition at line 160 of file arm_controller.cpp.

bool ArmController::setKinematicsPoseMsgCallback ( open_manipulator_msgs::SetKinematicsPose::Request &  req,
open_manipulator_msgs::SetKinematicsPose::Response &  res 
)
private

Definition at line 167 of file arm_controller.cpp.

Member Data Documentation

uint16_t open_manipulator::ArmController::all_time_steps_
private

Definition at line 99 of file arm_controller.h.

ros::Publisher open_manipulator::ArmController::arm_state_pub_
private

Definition at line 80 of file arm_controller.h.

ros::Subscriber open_manipulator::ArmController::display_planned_path_sub_
private

Definition at line 83 of file arm_controller.h.

ros::Publisher open_manipulator::ArmController::gazebo_goal_joint_position_pub_[10]
private

Definition at line 78 of file arm_controller.h.

ros::ServiceServer open_manipulator::ArmController::get_joint_position_server_
private

Definition at line 86 of file arm_controller.h.

ros::ServiceServer open_manipulator::ArmController::get_kinematics_pose_server_
private

Definition at line 87 of file arm_controller.h.

ros::Publisher open_manipulator::ArmController::goal_joint_position_pub_
private

Definition at line 79 of file arm_controller.h.

bool open_manipulator::ArmController::init_position_
private

Definition at line 75 of file arm_controller.h.

bool open_manipulator::ArmController::is_moving_
private

Definition at line 98 of file arm_controller.h.

int open_manipulator::ArmController::joint_num_
private

Definition at line 74 of file arm_controller.h.

moveit::planning_interface::MoveGroupInterface* open_manipulator::ArmController::move_group
private

Definition at line 94 of file arm_controller.h.

ros::NodeHandle open_manipulator::ArmController::nh_
private

Definition at line 68 of file arm_controller.h.

PlannedPathInfo open_manipulator::ArmController::planned_path_info_
private

Definition at line 95 of file arm_controller.h.

ros::NodeHandle open_manipulator::ArmController::priv_nh_
private

Definition at line 69 of file arm_controller.h.

std::string open_manipulator::ArmController::robot_name_
private

Definition at line 73 of file arm_controller.h.

ros::ServiceServer open_manipulator::ArmController::set_joint_position_server_
private

Definition at line 88 of file arm_controller.h.

ros::ServiceServer open_manipulator::ArmController::set_kinematics_pose_server_
private

Definition at line 89 of file arm_controller.h.

bool open_manipulator::ArmController::using_gazebo_
private

Definition at line 72 of file arm_controller.h.


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


open_manipulator_position_ctrl
Author(s): Darby Lim
autogenerated on Sat Jun 2 2018 02:43:38