Public Member Functions | Static Public Member Functions | Private Attributes | List of all members
open_manipulator_controller::OpenManipulatorController Class Reference

#include <open_manipulator_controller.h>

Public Member Functions

bool calcPlannedPath (const std::string planning_group, open_manipulator_msgs::JointPosition msg)
 
bool calcPlannedPath (const std::string planning_group, open_manipulator_msgs::KinematicsPose msg)
 
void displayPlannedPathCallback (const moveit_msgs::DisplayTrajectory::ConstPtr &msg)
 
void executeTrajGoalCallback (const moveit_msgs::ExecuteTrajectoryActionGoal::ConstPtr &msg)
 
double getControlPeriod (void)
 
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)
 
bool goalDrawingTrajectoryCallback (open_manipulator_msgs::SetDrawingTrajectory::Request &req, open_manipulator_msgs::SetDrawingTrajectory::Response &res)
 
bool goalJointSpacePathCallback (open_manipulator_msgs::SetJointPosition::Request &req, open_manipulator_msgs::SetJointPosition::Response &res)
 
bool goalJointSpacePathFromPresentCallback (open_manipulator_msgs::SetJointPosition::Request &req, open_manipulator_msgs::SetJointPosition::Response &res)
 
bool goalJointSpacePathToKinematicsOrientationCallback (open_manipulator_msgs::SetKinematicsPose::Request &req, open_manipulator_msgs::SetKinematicsPose::Response &res)
 
bool goalJointSpacePathToKinematicsPoseCallback (open_manipulator_msgs::SetKinematicsPose::Request &req, open_manipulator_msgs::SetKinematicsPose::Response &res)
 
bool goalJointSpacePathToKinematicsPositionCallback (open_manipulator_msgs::SetKinematicsPose::Request &req, open_manipulator_msgs::SetKinematicsPose::Response &res)
 
bool goalTaskSpacePathCallback (open_manipulator_msgs::SetKinematicsPose::Request &req, open_manipulator_msgs::SetKinematicsPose::Response &res)
 
bool goalTaskSpacePathFromPresentCallback (open_manipulator_msgs::SetKinematicsPose::Request &req, open_manipulator_msgs::SetKinematicsPose::Response &res)
 
bool goalTaskSpacePathFromPresentOrientationOnlyCallback (open_manipulator_msgs::SetKinematicsPose::Request &req, open_manipulator_msgs::SetKinematicsPose::Response &res)
 
bool goalTaskSpacePathFromPresentPositionOnlyCallback (open_manipulator_msgs::SetKinematicsPose::Request &req, open_manipulator_msgs::SetKinematicsPose::Response &res)
 
bool goalTaskSpacePathOrientationOnlyCallback (open_manipulator_msgs::SetKinematicsPose::Request &req, open_manipulator_msgs::SetKinematicsPose::Response &res)
 
bool goalTaskSpacePathPositionOnlyCallback (open_manipulator_msgs::SetKinematicsPose::Request &req, open_manipulator_msgs::SetKinematicsPose::Response &res)
 
bool goalToolControlCallback (open_manipulator_msgs::SetJointPosition::Request &req, open_manipulator_msgs::SetJointPosition::Response &res)
 
void initPublisher ()
 
void initServer ()
 
void initSubscriber ()
 
void moveGroupGoalCallback (const moveit_msgs::MoveGroupActionGoal::ConstPtr &msg)
 
void moveitTimer (double present_time)
 
 OpenManipulatorController (std::string usb_port, std::string baud_rate)
 
void openManipulatorOptionCallback (const std_msgs::String::ConstPtr &msg)
 
void process (double time)
 
void publishCallback (const ros::TimerEvent &)
 
void publishGazeboCommand ()
 
void publishJointStates ()
 
void publishKinematicsPose ()
 
void publishOpenManipulatorStates ()
 
bool setActuatorStateCallback (open_manipulator_msgs::SetActuatorState::Request &req, open_manipulator_msgs::SetActuatorState::Response &res)
 
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)
 
void startTimerThread ()
 
 ~OpenManipulatorController ()
 

Static Public Member Functions

static void * timerThread (void *param)
 

Private Attributes

pthread_attr_t attr_
 
double control_period_
 
ros::Subscriber display_planned_path_sub_
 
ros::Subscriber execute_traj_goal_sub_
 
std::vector< ros::Publishergazebo_goal_joint_position_pub_
 
ros::ServiceServer get_joint_position_server_
 
ros::ServiceServer get_kinematics_pose_server_
 
ros::ServiceServer goal_drawing_trajectory_server_
 
ros::ServiceServer goal_joint_space_path_from_present_server_
 
ros::ServiceServer goal_joint_space_path_server_
 
ros::ServiceServer goal_joint_space_path_to_kinematics_orientation_server_
 
ros::ServiceServer goal_joint_space_path_to_kinematics_pose_server_
 
ros::ServiceServer goal_joint_space_path_to_kinematics_position_server_
 
ros::ServiceServer goal_task_space_path_from_present_orientation_only_server_
 
ros::ServiceServer goal_task_space_path_from_present_position_only_server_
 
ros::ServiceServer goal_task_space_path_from_present_server_
 
ros::ServiceServer goal_task_space_path_orientation_only_server_
 
ros::ServiceServer goal_task_space_path_position_only_server_
 
ros::ServiceServer goal_task_space_path_server_
 
ros::ServiceServer goal_tool_control_server_
 
trajectory_msgs::JointTrajectory joint_trajectory_
 
moveit::planning_interface::MoveGroupInterfacemove_group_
 
ros::Subscriber move_group_goal_sub_
 
bool moveit_plan_only_
 
bool moveit_plan_state_
 
double moveit_sampling_time_
 
ros::Publisher moveit_update_start_state_pub_
 
ros::NodeHandle node_handle_
 
OpenManipulator open_manipulator_
 
ros::Publisher open_manipulator_joint_states_pub_
 
std::vector< ros::Publisheropen_manipulator_kinematics_pose_pub_
 
ros::Subscriber open_manipulator_option_sub_
 
ros::Publisher open_manipulator_states_pub_
 
ros::NodeHandle priv_node_handle_
 
ros::ServiceServer set_actuator_state_server_
 
ros::ServiceServer set_joint_position_server_
 
ros::ServiceServer set_kinematics_pose_server_
 
pthread_t timer_thread_
 
bool timer_thread_state_
 
bool tool_ctrl_state_
 
bool using_moveit_
 
bool using_platform_
 

Detailed Description

Definition at line 58 of file open_manipulator_controller.h.

Constructor & Destructor Documentation

OpenManipulatorController::OpenManipulatorController ( std::string  usb_port,
std::string  baud_rate 
)

Definition at line 23 of file open_manipulator_controller.cpp.

OpenManipulatorController::~OpenManipulatorController ( )

Definition at line 53 of file open_manipulator_controller.cpp.

Member Function Documentation

bool OpenManipulatorController::calcPlannedPath ( const std::string  planning_group,
open_manipulator_msgs::JointPosition  msg 
)

Definition at line 607 of file open_manipulator_controller.cpp.

bool OpenManipulatorController::calcPlannedPath ( const std::string  planning_group,
open_manipulator_msgs::KinematicsPose  msg 
)

Definition at line 566 of file open_manipulator_controller.cpp.

void OpenManipulatorController::displayPlannedPathCallback ( const moveit_msgs::DisplayTrajectory::ConstPtr &  msg)

Definition at line 217 of file open_manipulator_controller.cpp.

void OpenManipulatorController::executeTrajGoalCallback ( const moveit_msgs::ExecuteTrajectoryActionGoal::ConstPtr &  msg)

Definition at line 237 of file open_manipulator_controller.cpp.

double open_manipulator_controller::OpenManipulatorController::getControlPeriod ( void  )
inline

Definition at line 138 of file open_manipulator_controller.h.

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

Definition at line 514 of file open_manipulator_controller.cpp.

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

Definition at line 533 of file open_manipulator_controller.cpp.

bool OpenManipulatorController::goalDrawingTrajectoryCallback ( open_manipulator_msgs::SetDrawingTrajectory::Request &  req,
open_manipulator_msgs::SetDrawingTrajectory::Response &  res 
)

Definition at line 459 of file open_manipulator_controller.cpp.

bool OpenManipulatorController::goalJointSpacePathCallback ( open_manipulator_msgs::SetJointPosition::Request &  req,
open_manipulator_msgs::SetJointPosition::Response &  res 
)

Definition at line 243 of file open_manipulator_controller.cpp.

bool OpenManipulatorController::goalJointSpacePathFromPresentCallback ( open_manipulator_msgs::SetJointPosition::Request &  req,
open_manipulator_msgs::SetJointPosition::Response &  res 
)

Definition at line 360 of file open_manipulator_controller.cpp.

bool OpenManipulatorController::goalJointSpacePathToKinematicsOrientationCallback ( open_manipulator_msgs::SetKinematicsPose::Request &  req,
open_manipulator_msgs::SetKinematicsPose::Response &  res 
)

Definition at line 292 of file open_manipulator_controller.cpp.

bool OpenManipulatorController::goalJointSpacePathToKinematicsPoseCallback ( open_manipulator_msgs::SetKinematicsPose::Request &  req,
open_manipulator_msgs::SetKinematicsPose::Response &  res 
)

Definition at line 257 of file open_manipulator_controller.cpp.

bool OpenManipulatorController::goalJointSpacePathToKinematicsPositionCallback ( open_manipulator_msgs::SetKinematicsPose::Request &  req,
open_manipulator_msgs::SetKinematicsPose::Response &  res 
)

Definition at line 278 of file open_manipulator_controller.cpp.

bool OpenManipulatorController::goalTaskSpacePathCallback ( open_manipulator_msgs::SetKinematicsPose::Request &  req,
open_manipulator_msgs::SetKinematicsPose::Response &  res 
)

Definition at line 310 of file open_manipulator_controller.cpp.

bool OpenManipulatorController::goalTaskSpacePathFromPresentCallback ( open_manipulator_msgs::SetKinematicsPose::Request &  req,
open_manipulator_msgs::SetKinematicsPose::Response &  res 
)

Definition at line 374 of file open_manipulator_controller.cpp.

bool OpenManipulatorController::goalTaskSpacePathFromPresentOrientationOnlyCallback ( open_manipulator_msgs::SetKinematicsPose::Request &  req,
open_manipulator_msgs::SetKinematicsPose::Response &  res 
)

Definition at line 409 of file open_manipulator_controller.cpp.

bool OpenManipulatorController::goalTaskSpacePathFromPresentPositionOnlyCallback ( open_manipulator_msgs::SetKinematicsPose::Request &  req,
open_manipulator_msgs::SetKinematicsPose::Response &  res 
)

Definition at line 395 of file open_manipulator_controller.cpp.

bool OpenManipulatorController::goalTaskSpacePathOrientationOnlyCallback ( open_manipulator_msgs::SetKinematicsPose::Request &  req,
open_manipulator_msgs::SetKinematicsPose::Response &  res 
)

Definition at line 344 of file open_manipulator_controller.cpp.

bool OpenManipulatorController::goalTaskSpacePathPositionOnlyCallback ( open_manipulator_msgs::SetKinematicsPose::Request &  req,
open_manipulator_msgs::SetKinematicsPose::Response &  res 
)

Definition at line 330 of file open_manipulator_controller.cpp.

bool OpenManipulatorController::goalToolControlCallback ( open_manipulator_msgs::SetJointPosition::Request &  req,
open_manipulator_msgs::SetJointPosition::Response &  res 
)

Definition at line 425 of file open_manipulator_controller.cpp.

void OpenManipulatorController::initPublisher ( )

Definition at line 131 of file open_manipulator_controller.cpp.

void OpenManipulatorController::initServer ( )

Definition at line 181 of file open_manipulator_controller.cpp.

void OpenManipulatorController::initSubscriber ( )

Definition at line 166 of file open_manipulator_controller.cpp.

void OpenManipulatorController::moveGroupGoalCallback ( const moveit_msgs::MoveGroupActionGoal::ConstPtr &  msg)

Definition at line 231 of file open_manipulator_controller.cpp.

void OpenManipulatorController::moveitTimer ( double  present_time)

Definition at line 758 of file open_manipulator_controller.cpp.

void OpenManipulatorController::openManipulatorOptionCallback ( const std_msgs::String::ConstPtr &  msg)

Definition at line 211 of file open_manipulator_controller.cpp.

void OpenManipulatorController::process ( double  time)

Definition at line 803 of file open_manipulator_controller.cpp.

void OpenManipulatorController::publishCallback ( const ros::TimerEvent )

Definition at line 749 of file open_manipulator_controller.cpp.

void OpenManipulatorController::publishGazeboCommand ( )

Definition at line 727 of file open_manipulator_controller.cpp.

void OpenManipulatorController::publishJointStates ( )

Definition at line 696 of file open_manipulator_controller.cpp.

void OpenManipulatorController::publishKinematicsPose ( )

Definition at line 673 of file open_manipulator_controller.cpp.

void OpenManipulatorController::publishOpenManipulatorStates ( )

Definition at line 657 of file open_manipulator_controller.cpp.

bool OpenManipulatorController::setActuatorStateCallback ( open_manipulator_msgs::SetActuatorState::Request &  req,
open_manipulator_msgs::SetActuatorState::Response &  res 
)

Definition at line 435 of file open_manipulator_controller.cpp.

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

Definition at line 548 of file open_manipulator_controller.cpp.

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

Definition at line 557 of file open_manipulator_controller.cpp.

void OpenManipulatorController::startTimerThread ( )

Use this when you want to increase the priority of threads.

Definition at line 62 of file open_manipulator_controller.cpp.

void * OpenManipulatorController::timerThread ( void *  param)
static

Definition at line 99 of file open_manipulator_controller.cpp.

Member Data Documentation

pthread_attr_t open_manipulator_controller::OpenManipulatorController::attr_
private

Definition at line 111 of file open_manipulator_controller.h.

double open_manipulator_controller::OpenManipulatorController::control_period_
private

Definition at line 68 of file open_manipulator_controller.h.

ros::Subscriber open_manipulator_controller::OpenManipulatorController::display_planned_path_sub_
private

Definition at line 79 of file open_manipulator_controller.h.

ros::Subscriber open_manipulator_controller::OpenManipulatorController::execute_traj_goal_sub_
private

Definition at line 81 of file open_manipulator_controller.h.

std::vector<ros::Publisher> open_manipulator_controller::OpenManipulatorController::gazebo_goal_joint_position_pub_
private

Definition at line 74 of file open_manipulator_controller.h.

ros::ServiceServer open_manipulator_controller::OpenManipulatorController::get_joint_position_server_
private

Definition at line 98 of file open_manipulator_controller.h.

ros::ServiceServer open_manipulator_controller::OpenManipulatorController::get_kinematics_pose_server_
private

Definition at line 99 of file open_manipulator_controller.h.

ros::ServiceServer open_manipulator_controller::OpenManipulatorController::goal_drawing_trajectory_server_
private

Definition at line 97 of file open_manipulator_controller.h.

ros::ServiceServer open_manipulator_controller::OpenManipulatorController::goal_joint_space_path_from_present_server_
private

Definition at line 91 of file open_manipulator_controller.h.

ros::ServiceServer open_manipulator_controller::OpenManipulatorController::goal_joint_space_path_server_
private

Definition at line 84 of file open_manipulator_controller.h.

ros::ServiceServer open_manipulator_controller::OpenManipulatorController::goal_joint_space_path_to_kinematics_orientation_server_
private

Definition at line 87 of file open_manipulator_controller.h.

ros::ServiceServer open_manipulator_controller::OpenManipulatorController::goal_joint_space_path_to_kinematics_pose_server_
private

Definition at line 85 of file open_manipulator_controller.h.

ros::ServiceServer open_manipulator_controller::OpenManipulatorController::goal_joint_space_path_to_kinematics_position_server_
private

Definition at line 86 of file open_manipulator_controller.h.

ros::ServiceServer open_manipulator_controller::OpenManipulatorController::goal_task_space_path_from_present_orientation_only_server_
private

Definition at line 93 of file open_manipulator_controller.h.

ros::ServiceServer open_manipulator_controller::OpenManipulatorController::goal_task_space_path_from_present_position_only_server_
private

Definition at line 92 of file open_manipulator_controller.h.

ros::ServiceServer open_manipulator_controller::OpenManipulatorController::goal_task_space_path_from_present_server_
private

Definition at line 94 of file open_manipulator_controller.h.

ros::ServiceServer open_manipulator_controller::OpenManipulatorController::goal_task_space_path_orientation_only_server_
private

Definition at line 90 of file open_manipulator_controller.h.

ros::ServiceServer open_manipulator_controller::OpenManipulatorController::goal_task_space_path_position_only_server_
private

Definition at line 89 of file open_manipulator_controller.h.

ros::ServiceServer open_manipulator_controller::OpenManipulatorController::goal_task_space_path_server_
private

Definition at line 88 of file open_manipulator_controller.h.

ros::ServiceServer open_manipulator_controller::OpenManipulatorController::goal_tool_control_server_
private

Definition at line 95 of file open_manipulator_controller.h.

trajectory_msgs::JointTrajectory open_manipulator_controller::OpenManipulatorController::joint_trajectory_
private

Definition at line 105 of file open_manipulator_controller.h.

moveit::planning_interface::MoveGroupInterface* open_manipulator_controller::OpenManipulatorController::move_group_
private

Definition at line 104 of file open_manipulator_controller.h.

ros::Subscriber open_manipulator_controller::OpenManipulatorController::move_group_goal_sub_
private

Definition at line 80 of file open_manipulator_controller.h.

bool open_manipulator_controller::OpenManipulatorController::moveit_plan_only_
private

Definition at line 107 of file open_manipulator_controller.h.

bool open_manipulator_controller::OpenManipulatorController::moveit_plan_state_
private

Definition at line 119 of file open_manipulator_controller.h.

double open_manipulator_controller::OpenManipulatorController::moveit_sampling_time_
private

Definition at line 106 of file open_manipulator_controller.h.

ros::Publisher open_manipulator_controller::OpenManipulatorController::moveit_update_start_state_pub_
private

Definition at line 75 of file open_manipulator_controller.h.

ros::NodeHandle open_manipulator_controller::OpenManipulatorController::node_handle_
private

Definition at line 62 of file open_manipulator_controller.h.

OpenManipulator open_manipulator_controller::OpenManipulatorController::open_manipulator_
private

Definition at line 114 of file open_manipulator_controller.h.

ros::Publisher open_manipulator_controller::OpenManipulatorController::open_manipulator_joint_states_pub_
private

Definition at line 73 of file open_manipulator_controller.h.

std::vector<ros::Publisher> open_manipulator_controller::OpenManipulatorController::open_manipulator_kinematics_pose_pub_
private

Definition at line 72 of file open_manipulator_controller.h.

ros::Subscriber open_manipulator_controller::OpenManipulatorController::open_manipulator_option_sub_
private

Definition at line 78 of file open_manipulator_controller.h.

ros::Publisher open_manipulator_controller::OpenManipulatorController::open_manipulator_states_pub_
private

Definition at line 71 of file open_manipulator_controller.h.

ros::NodeHandle open_manipulator_controller::OpenManipulatorController::priv_node_handle_
private

Definition at line 63 of file open_manipulator_controller.h.

ros::ServiceServer open_manipulator_controller::OpenManipulatorController::set_actuator_state_server_
private

Definition at line 96 of file open_manipulator_controller.h.

ros::ServiceServer open_manipulator_controller::OpenManipulatorController::set_joint_position_server_
private

Definition at line 100 of file open_manipulator_controller.h.

ros::ServiceServer open_manipulator_controller::OpenManipulatorController::set_kinematics_pose_server_
private

Definition at line 101 of file open_manipulator_controller.h.

pthread_t open_manipulator_controller::OpenManipulatorController::timer_thread_
private

Definition at line 110 of file open_manipulator_controller.h.

bool open_manipulator_controller::OpenManipulatorController::timer_thread_state_
private

Definition at line 118 of file open_manipulator_controller.h.

bool open_manipulator_controller::OpenManipulatorController::tool_ctrl_state_
private

Definition at line 117 of file open_manipulator_controller.h.

bool open_manipulator_controller::OpenManipulatorController::using_moveit_
private

Definition at line 67 of file open_manipulator_controller.h.

bool open_manipulator_controller::OpenManipulatorController::using_platform_
private

Definition at line 66 of file open_manipulator_controller.h.


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


open_manipulator_controller
Author(s): Darby Lim , Hye-Jong KIM , Ryan Shim , Yong-Ho Na
autogenerated on Mon Jun 10 2019 14:12:06