TF. More...
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_aubo::AuboHardwareInterface > | hardware_interface_ |
bool | has_goal_ |
double | io_flag_delay_ |
ros::ServiceServer | io_srv_ |
std::vector< double > | joint_offsets_ |
double | max_velocity_ |
ros::Subscriber | move_sub_ |
std::condition_variable | msg_cond_ |
ros::NodeHandle | nh_ |
control_msgs::FollowJointTrajectoryResult | result_ |
AuboNewDriver | robot_ |
std::thread * | ros_control_thread_ |
std::condition_variable | rt_msg_cond_ |
std::thread * | rt_publish_thread_ |
ros::Subscriber | script_sub_ |
ros::Subscriber | speed_sub_ |
std::string | tool_frame_ |
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 | moveInterface (const std_msgs::Float32MultiArray::ConstPtr &msg) |
void | publishRTMsg () |
void | reorder_traj_joints (trajectory_msgs::JointTrajectory &traj) |
void | rosControlLoop () |
void | scriptInterface (const std_msgs::String::ConstPtr &msg) |
bool | setIO (aubo_msgs::SetIORequest &req, aubo_msgs::SetIOResponse &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) |
bool | validateJointNames () |
TF.
Definition at line 37 of file aubo_ros_wrapper.cpp.
RosWrapper::RosWrapper | ( | std::string | host, |
int | reverse_port | ||
) | [inline] |
Definition at line 64 of file aubo_ros_wrapper.cpp.
void RosWrapper::cancelCB | ( | actionlib::ServerGoalHandle< control_msgs::FollowJointTrajectoryAction > | gh | ) | [inline, private] |
Definition at line 288 of file aubo_ros_wrapper.cpp.
void RosWrapper::goalCB | ( | actionlib::ServerGoalHandle< control_msgs::FollowJointTrajectoryAction > | gh | ) | [inline, private] |
Definition at line 188 of file aubo_ros_wrapper.cpp.
void RosWrapper::halt | ( | ) | [inline] |
Definition at line 171 of file aubo_ros_wrapper.cpp.
bool RosWrapper::has_limited_velocities | ( | ) | [inline, private] |
Definition at line 403 of file aubo_ros_wrapper.cpp.
bool RosWrapper::has_positions | ( | ) | [inline, private] |
Definition at line 377 of file aubo_ros_wrapper.cpp.
bool RosWrapper::has_velocities | ( | ) | [inline, private] |
Definition at line 366 of file aubo_ros_wrapper.cpp.
void RosWrapper::moveInterface | ( | const std_msgs::Float32MultiArray::ConstPtr & | msg | ) | [inline, private] |
Definition at line 455 of file aubo_ros_wrapper.cpp.
void RosWrapper::publishRTMsg | ( | ) | [inline, private] |
Definition at line 495 of file aubo_ros_wrapper.cpp.
void RosWrapper::reorder_traj_joints | ( | trajectory_msgs::JointTrajectory & | traj | ) | [inline, private] |
Definition at line 336 of file aubo_ros_wrapper.cpp.
void RosWrapper::rosControlLoop | ( | ) | [inline, private] |
Definition at line 468 of file aubo_ros_wrapper.cpp.
void RosWrapper::scriptInterface | ( | const std_msgs::String::ConstPtr & | msg | ) | [inline, private] |
Definition at line 448 of file aubo_ros_wrapper.cpp.
bool RosWrapper::setIO | ( | aubo_msgs::SetIORequest & | req, |
aubo_msgs::SetIOResponse & | resp | ||
) | [inline, private] |
Definition at line 303 of file aubo_ros_wrapper.cpp.
void RosWrapper::speedInterface | ( | const trajectory_msgs::JointTrajectory::Ptr & | msg | ) | [inline, private] |
Definition at line 432 of file aubo_ros_wrapper.cpp.
bool RosWrapper::start_positions_match | ( | const trajectory_msgs::JointTrajectory & | traj, |
double | eps | ||
) | [inline, private] |
Definition at line 390 of file aubo_ros_wrapper.cpp.
bool RosWrapper::traj_is_finite | ( | ) | [inline, private] |
Definition at line 417 of file aubo_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 177 of file aubo_ros_wrapper.cpp.
bool RosWrapper::validateJointNames | ( | ) | [inline, private] |
Definition at line 313 of file aubo_ros_wrapper.cpp.
actionlib::ActionServer<control_msgs::FollowJointTrajectoryAction> RosWrapper::as_ [protected] |
Definition at line 43 of file aubo_ros_wrapper.cpp.
std::string RosWrapper::base_frame_ [protected] |
Definition at line 56 of file aubo_ros_wrapper.cpp.
boost::shared_ptr<controller_manager::ControllerManager> RosWrapper::controller_manager_ [protected] |
Definition at line 61 of file aubo_ros_wrapper.cpp.
control_msgs::FollowJointTrajectoryFeedback RosWrapper::feedback_ [protected] |
Definition at line 46 of file aubo_ros_wrapper.cpp.
actionlib::ServerGoalHandle<control_msgs::FollowJointTrajectoryAction> RosWrapper::goal_handle_ [protected] |
Definition at line 44 of file aubo_ros_wrapper.cpp.
boost::shared_ptr<ros_control_aubo::AuboHardwareInterface> RosWrapper::hardware_interface_ [protected] |
Definition at line 60 of file aubo_ros_wrapper.cpp.
bool RosWrapper::has_goal_ [protected] |
Definition at line 45 of file aubo_ros_wrapper.cpp.
double RosWrapper::io_flag_delay_ [protected] |
Definition at line 53 of file aubo_ros_wrapper.cpp.
ros::ServiceServer RosWrapper::io_srv_ [protected] |
Definition at line 51 of file aubo_ros_wrapper.cpp.
std::vector<double> RosWrapper::joint_offsets_ [protected] |
Definition at line 55 of file aubo_ros_wrapper.cpp.
double RosWrapper::max_velocity_ [protected] |
Definition at line 54 of file aubo_ros_wrapper.cpp.
ros::Subscriber RosWrapper::move_sub_ [protected] |
Definition at line 50 of file aubo_ros_wrapper.cpp.
std::condition_variable RosWrapper::msg_cond_ [protected] |
Definition at line 41 of file aubo_ros_wrapper.cpp.
ros::NodeHandle RosWrapper::nh_ [protected] |
Definition at line 42 of file aubo_ros_wrapper.cpp.
control_msgs::FollowJointTrajectoryResult RosWrapper::result_ [protected] |
Definition at line 47 of file aubo_ros_wrapper.cpp.
AuboNewDriver RosWrapper::robot_ [protected] |
Definition at line 39 of file aubo_ros_wrapper.cpp.
std::thread* RosWrapper::ros_control_thread_ [protected] |
Definition at line 59 of file aubo_ros_wrapper.cpp.
std::condition_variable RosWrapper::rt_msg_cond_ [protected] |
Definition at line 40 of file aubo_ros_wrapper.cpp.
std::thread* RosWrapper::rt_publish_thread_ [protected] |
Definition at line 52 of file aubo_ros_wrapper.cpp.
ros::Subscriber RosWrapper::script_sub_ [protected] |
Definition at line 49 of file aubo_ros_wrapper.cpp.
ros::Subscriber RosWrapper::speed_sub_ [protected] |
Definition at line 48 of file aubo_ros_wrapper.cpp.
std::string RosWrapper::tool_frame_ [protected] |
Definition at line 57 of file aubo_ros_wrapper.cpp.
bool RosWrapper::use_ros_control_ [protected] |
Definition at line 58 of file aubo_ros_wrapper.cpp.