Public Member Functions | Protected Attributes | Private Member Functions
RosWrapper Class Reference

TF. More...

List of all members.

Public Member Functions

void halt ()
 RosWrapper (std::string host, int reverse_port)

Protected Attributes

actionlib::ActionServer
< control_msgs::FollowJointTrajectoryAction > 
as_
std::string base_frame_
boost::shared_ptr
< controller_manager::ControllerManager
controller_manager_
control_msgs::FollowJointTrajectoryFeedback feedback_
actionlib::ServerGoalHandle
< control_msgs::FollowJointTrajectoryAction > 
goal_handle_
boost::shared_ptr
< ros_control_ur::UrHardwareInterface
hardware_interface_
bool has_goal_
double io_flag_delay_
ros::ServiceServer io_srv_
std::vector< double > joint_offsets_
double max_velocity_
std::thread * mb_publish_thread_
std::condition_variable msg_cond_
ros::NodeHandle nh_
ros::ServiceServer payload_srv_
control_msgs::FollowJointTrajectoryResult result_
UrDriver robot_
std::thread * ros_control_thread_
std::condition_variable rt_msg_cond_
std::thread * rt_publish_thread_
ros::Subscriber speed_sub_
std::string tool_frame_
ros::Subscriber urscript_sub_
bool use_ros_control_

Private Member Functions

void cancelCB (actionlib::ServerGoalHandle< control_msgs::FollowJointTrajectoryAction > gh)
void goalCB (actionlib::ServerGoalHandle< control_msgs::FollowJointTrajectoryAction > gh)
bool has_limited_velocities ()
bool has_positions ()
bool has_velocities ()
void publishMbMsg ()
void publishRTMsg ()
void reorder_traj_joints (trajectory_msgs::JointTrajectory &traj)
void rosControlLoop ()
bool setIO (ur_msgs::SetIORequest &req, ur_msgs::SetIOResponse &resp)
bool setPayload (ur_msgs::SetPayloadRequest &req, ur_msgs::SetPayloadResponse &resp)
void speedInterface (const trajectory_msgs::JointTrajectory::Ptr &msg)
bool start_positions_match (const trajectory_msgs::JointTrajectory &traj, double eps)
bool traj_is_finite ()
void trajThread (std::vector< double > timestamps, std::vector< std::vector< double > > positions, std::vector< std::vector< double > > velocities)
void urscriptInterface (const std_msgs::String::ConstPtr &msg)
bool validateJointNames ()

Detailed Description

TF.

Definition at line 58 of file ur_ros_wrapper.cpp.


Constructor & Destructor Documentation

RosWrapper::RosWrapper ( std::string  host,
int  reverse_port 
) [inline]

Definition at line 86 of file ur_ros_wrapper.cpp.


Member Function Documentation

void RosWrapper::cancelCB ( actionlib::ServerGoalHandle< control_msgs::FollowJointTrajectoryAction >  gh) [inline, private]

Definition at line 380 of file ur_ros_wrapper.cpp.

void RosWrapper::goalCB ( actionlib::ServerGoalHandle< control_msgs::FollowJointTrajectoryAction >  gh) [inline, private]

Definition at line 236 of file ur_ros_wrapper.cpp.

void RosWrapper::halt ( ) [inline]

Definition at line 219 of file ur_ros_wrapper.cpp.

bool RosWrapper::has_limited_velocities ( ) [inline, private]

Definition at line 517 of file ur_ros_wrapper.cpp.

bool RosWrapper::has_positions ( ) [inline, private]

Definition at line 491 of file ur_ros_wrapper.cpp.

bool RosWrapper::has_velocities ( ) [inline, private]

Definition at line 480 of file ur_ros_wrapper.cpp.

void RosWrapper::publishMbMsg ( ) [inline, private]

Definition at line 728 of file ur_ros_wrapper.cpp.

void RosWrapper::publishRTMsg ( ) [inline, private]

Definition at line 651 of file ur_ros_wrapper.cpp.

void RosWrapper::reorder_traj_joints ( trajectory_msgs::JointTrajectory &  traj) [inline, private]

Definition at line 450 of file ur_ros_wrapper.cpp.

void RosWrapper::rosControlLoop ( ) [inline, private]

Definition at line 565 of file ur_ros_wrapper.cpp.

bool RosWrapper::setIO ( ur_msgs::SetIORequest &  req,
ur_msgs::SetIOResponse &  resp 
) [inline, private]

Definition at line 396 of file ur_ros_wrapper.cpp.

bool RosWrapper::setPayload ( ur_msgs::SetPayloadRequest &  req,
ur_msgs::SetPayloadResponse &  resp 
) [inline, private]

Definition at line 418 of file ur_ros_wrapper.cpp.

void RosWrapper::speedInterface ( const trajectory_msgs::JointTrajectory::Ptr &  msg) [inline, private]

Definition at line 546 of file ur_ros_wrapper.cpp.

bool RosWrapper::start_positions_match ( const trajectory_msgs::JointTrajectory &  traj,
double  eps 
) [inline, private]

Definition at line 504 of file ur_ros_wrapper.cpp.

bool RosWrapper::traj_is_finite ( ) [inline, private]

Definition at line 531 of file ur_ros_wrapper.cpp.

void RosWrapper::trajThread ( std::vector< double >  timestamps,
std::vector< std::vector< double > >  positions,
std::vector< std::vector< double > >  velocities 
) [inline, private]

Definition at line 225 of file ur_ros_wrapper.cpp.

void RosWrapper::urscriptInterface ( const std_msgs::String::ConstPtr &  msg) [inline, private]

Definition at line 559 of file ur_ros_wrapper.cpp.

bool RosWrapper::validateJointNames ( ) [inline, private]

Definition at line 427 of file ur_ros_wrapper.cpp.


Member Data Documentation

actionlib::ActionServer<control_msgs::FollowJointTrajectoryAction> RosWrapper::as_ [protected]

Definition at line 64 of file ur_ros_wrapper.cpp.

std::string RosWrapper::base_frame_ [protected]

Definition at line 78 of file ur_ros_wrapper.cpp.

Definition at line 83 of file ur_ros_wrapper.cpp.

control_msgs::FollowJointTrajectoryFeedback RosWrapper::feedback_ [protected]

Definition at line 67 of file ur_ros_wrapper.cpp.

actionlib::ServerGoalHandle<control_msgs::FollowJointTrajectoryAction> RosWrapper::goal_handle_ [protected]

Definition at line 65 of file ur_ros_wrapper.cpp.

Definition at line 82 of file ur_ros_wrapper.cpp.

bool RosWrapper::has_goal_ [protected]

Definition at line 66 of file ur_ros_wrapper.cpp.

double RosWrapper::io_flag_delay_ [protected]

Definition at line 75 of file ur_ros_wrapper.cpp.

Definition at line 71 of file ur_ros_wrapper.cpp.

std::vector<double> RosWrapper::joint_offsets_ [protected]

Definition at line 77 of file ur_ros_wrapper.cpp.

double RosWrapper::max_velocity_ [protected]

Definition at line 76 of file ur_ros_wrapper.cpp.

std::thread* RosWrapper::mb_publish_thread_ [protected]

Definition at line 74 of file ur_ros_wrapper.cpp.

std::condition_variable RosWrapper::msg_cond_ [protected]

Definition at line 62 of file ur_ros_wrapper.cpp.

Definition at line 63 of file ur_ros_wrapper.cpp.

Definition at line 72 of file ur_ros_wrapper.cpp.

control_msgs::FollowJointTrajectoryResult RosWrapper::result_ [protected]

Definition at line 68 of file ur_ros_wrapper.cpp.

Definition at line 60 of file ur_ros_wrapper.cpp.

std::thread* RosWrapper::ros_control_thread_ [protected]

Definition at line 81 of file ur_ros_wrapper.cpp.

std::condition_variable RosWrapper::rt_msg_cond_ [protected]

Definition at line 61 of file ur_ros_wrapper.cpp.

std::thread* RosWrapper::rt_publish_thread_ [protected]

Definition at line 73 of file ur_ros_wrapper.cpp.

Definition at line 69 of file ur_ros_wrapper.cpp.

std::string RosWrapper::tool_frame_ [protected]

Definition at line 79 of file ur_ros_wrapper.cpp.

Definition at line 70 of file ur_ros_wrapper.cpp.

bool RosWrapper::use_ros_control_ [protected]

Definition at line 80 of file ur_ros_wrapper.cpp.


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


ur_modern_driver
Author(s): Thomas Timm Andersen
autogenerated on Wed Apr 3 2019 02:55:31