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

#include <open_manipulator_p_controller.h>

Public Member Functions

double getControlPeriod (void)
 
 OpenManipulatorController (std::string usb_port, std::string baud_rate)
 
void process (double time)
 
void publishCallback (const ros::TimerEvent &)
 
void startTimerThread ()
 
 ~OpenManipulatorController ()
 

Static Public Member Functions

static void * timerThread (void *param)
 

Private Member Functions

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 openManipulatorOptionCallback (const std_msgs::String::ConstPtr &msg)
 
void publishGazeboCommand ()
 
void publishJointStates ()
 
void publishKinematicsPose ()
 
void publishOpenManipulatorStates ()
 
bool setActuatorStateCallback (open_manipulator_msgs::SetActuatorState::Request &req, open_manipulator_msgs::SetActuatorState::Response &res)
 

Private Attributes

pthread_attr_t attr_
 
double control_period_
 
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_
 
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 using_platform_
 
bool with_gripper_
 

Detailed Description

Definition at line 45 of file open_manipulator_p_controller.h.

Constructor & Destructor Documentation

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

Definition at line 23 of file open_manipulator_p_controller.cpp.

OpenManipulatorController::~OpenManipulatorController ( )

Definition at line 52 of file open_manipulator_p_controller.cpp.

Member Function Documentation

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

Definition at line 56 of file open_manipulator_p_controller.h.

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

Definition at line 448 of file open_manipulator_p_controller.cpp.

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

Definition at line 204 of file open_manipulator_p_controller.cpp.

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

Definition at line 336 of file open_manipulator_p_controller.cpp.

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

Definition at line 259 of file open_manipulator_p_controller.cpp.

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

Definition at line 220 of file open_manipulator_p_controller.cpp.

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

Definition at line 243 of file open_manipulator_p_controller.cpp.

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

Definition at line 278 of file open_manipulator_p_controller.cpp.

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

Definition at line 352 of file open_manipulator_p_controller.cpp.

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

Definition at line 391 of file open_manipulator_p_controller.cpp.

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

Definition at line 375 of file open_manipulator_p_controller.cpp.

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

Definition at line 318 of file open_manipulator_p_controller.cpp.

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

Definition at line 302 of file open_manipulator_p_controller.cpp.

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

Definition at line 409 of file open_manipulator_p_controller.cpp.

void OpenManipulatorController::initPublisher ( )
private

Definition at line 133 of file open_manipulator_p_controller.cpp.

void OpenManipulatorController::initServer ( )
private

Definition at line 170 of file open_manipulator_p_controller.cpp.

void OpenManipulatorController::initSubscriber ( )
private

Definition at line 164 of file open_manipulator_p_controller.cpp.

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

Definition at line 195 of file open_manipulator_p_controller.cpp.

void OpenManipulatorController::process ( double  time)

Definition at line 519 of file open_manipulator_p_controller.cpp.

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

Definition at line 527 of file open_manipulator_p_controller.cpp.

void OpenManipulatorController::publishGazeboCommand ( )
private

Definition at line 606 of file open_manipulator_p_controller.cpp.

void OpenManipulatorController::publishJointStates ( )
private

Definition at line 575 of file open_manipulator_p_controller.cpp.

void OpenManipulatorController::publishKinematicsPose ( )
private

Definition at line 552 of file open_manipulator_p_controller.cpp.

void OpenManipulatorController::publishOpenManipulatorStates ( )
private

Definition at line 536 of file open_manipulator_p_controller.cpp.

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

Definition at line 423 of file open_manipulator_p_controller.cpp.

void OpenManipulatorController::startTimerThread ( )

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

Definition at line 61 of file open_manipulator_p_controller.cpp.

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

Definition at line 98 of file open_manipulator_p_controller.cpp.

Member Data Documentation

pthread_attr_t open_manipulator_p_controller::OpenManipulatorController::attr_
private

Definition at line 77 of file open_manipulator_p_controller.h.

double open_manipulator_p_controller::OpenManipulatorController::control_period_
private

Definition at line 69 of file open_manipulator_p_controller.h.

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

Definition at line 96 of file open_manipulator_p_controller.h.

ros::ServiceServer open_manipulator_p_controller::OpenManipulatorController::get_joint_position_server_
private

Definition at line 127 of file open_manipulator_p_controller.h.

ros::ServiceServer open_manipulator_p_controller::OpenManipulatorController::get_kinematics_pose_server_
private

Definition at line 128 of file open_manipulator_p_controller.h.

ros::ServiceServer open_manipulator_p_controller::OpenManipulatorController::goal_drawing_trajectory_server_
private

Definition at line 126 of file open_manipulator_p_controller.h.

ros::ServiceServer open_manipulator_p_controller::OpenManipulatorController::goal_joint_space_path_from_present_server_
private

Definition at line 120 of file open_manipulator_p_controller.h.

ros::ServiceServer open_manipulator_p_controller::OpenManipulatorController::goal_joint_space_path_server_
private

Definition at line 113 of file open_manipulator_p_controller.h.

ros::ServiceServer open_manipulator_p_controller::OpenManipulatorController::goal_joint_space_path_to_kinematics_orientation_server_
private

Definition at line 116 of file open_manipulator_p_controller.h.

ros::ServiceServer open_manipulator_p_controller::OpenManipulatorController::goal_joint_space_path_to_kinematics_pose_server_
private

Definition at line 114 of file open_manipulator_p_controller.h.

ros::ServiceServer open_manipulator_p_controller::OpenManipulatorController::goal_joint_space_path_to_kinematics_position_server_
private

Definition at line 115 of file open_manipulator_p_controller.h.

ros::ServiceServer open_manipulator_p_controller::OpenManipulatorController::goal_task_space_path_from_present_orientation_only_server_
private

Definition at line 122 of file open_manipulator_p_controller.h.

ros::ServiceServer open_manipulator_p_controller::OpenManipulatorController::goal_task_space_path_from_present_position_only_server_
private

Definition at line 121 of file open_manipulator_p_controller.h.

ros::ServiceServer open_manipulator_p_controller::OpenManipulatorController::goal_task_space_path_from_present_server_
private

Definition at line 123 of file open_manipulator_p_controller.h.

ros::ServiceServer open_manipulator_p_controller::OpenManipulatorController::goal_task_space_path_orientation_only_server_
private

Definition at line 119 of file open_manipulator_p_controller.h.

ros::ServiceServer open_manipulator_p_controller::OpenManipulatorController::goal_task_space_path_position_only_server_
private

Definition at line 118 of file open_manipulator_p_controller.h.

ros::ServiceServer open_manipulator_p_controller::OpenManipulatorController::goal_task_space_path_server_
private

Definition at line 117 of file open_manipulator_p_controller.h.

ros::ServiceServer open_manipulator_p_controller::OpenManipulatorController::goal_tool_control_server_
private

Definition at line 124 of file open_manipulator_p_controller.h.

ros::NodeHandle open_manipulator_p_controller::OpenManipulatorController::node_handle_
private

Definition at line 62 of file open_manipulator_p_controller.h.

OpenManipulator open_manipulator_p_controller::OpenManipulatorController::open_manipulator_
private

Definition at line 81 of file open_manipulator_p_controller.h.

ros::Publisher open_manipulator_p_controller::OpenManipulatorController::open_manipulator_joint_states_pub_
private

Definition at line 95 of file open_manipulator_p_controller.h.

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

Definition at line 94 of file open_manipulator_p_controller.h.

ros::Subscriber open_manipulator_p_controller::OpenManipulatorController::open_manipulator_option_sub_
private

Definition at line 106 of file open_manipulator_p_controller.h.

ros::Publisher open_manipulator_p_controller::OpenManipulatorController::open_manipulator_states_pub_
private

Definition at line 93 of file open_manipulator_p_controller.h.

ros::NodeHandle open_manipulator_p_controller::OpenManipulatorController::priv_node_handle_
private

Definition at line 63 of file open_manipulator_p_controller.h.

ros::ServiceServer open_manipulator_p_controller::OpenManipulatorController::set_actuator_state_server_
private

Definition at line 125 of file open_manipulator_p_controller.h.

ros::ServiceServer open_manipulator_p_controller::OpenManipulatorController::set_joint_position_server_
private

Definition at line 129 of file open_manipulator_p_controller.h.

ros::ServiceServer open_manipulator_p_controller::OpenManipulatorController::set_kinematics_pose_server_
private

Definition at line 130 of file open_manipulator_p_controller.h.

pthread_t open_manipulator_p_controller::OpenManipulatorController::timer_thread_
private

Definition at line 76 of file open_manipulator_p_controller.h.

bool open_manipulator_p_controller::OpenManipulatorController::timer_thread_state_
private

Definition at line 78 of file open_manipulator_p_controller.h.

bool open_manipulator_p_controller::OpenManipulatorController::using_platform_
private

Definition at line 68 of file open_manipulator_p_controller.h.

bool open_manipulator_p_controller::OpenManipulatorController::with_gripper_
private

Definition at line 70 of file open_manipulator_p_controller.h.


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


open_manipulator_p_controller
Author(s): Ryan Shim , Yong-Ho Na , Hye-Jong KIM
autogenerated on Thu Oct 22 2020 03:16:39