Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
fsrobo_r_driver::joint_trajectory_streamer::FSRoboRJointTrajectoryStreamer Class Reference

#include <fsrobo_r_joint_trajectory_streamer.h>

Inheritance diagram for fsrobo_r_driver::joint_trajectory_streamer::FSRoboRJointTrajectoryStreamer:
Inheritance graph
[legend]

Public Member Functions

 FSRoboRJointTrajectoryStreamer (int min_buffer_size=1)
 Default constructor. More...
 
virtual bool init (SmplMsgConnection *connection, const std::vector< std::string > &joint_names, const std::map< std::string, double > &velocity_limits=std::map< std::string, double >())
 Class initializer. More...
 
virtual void jointTrajectoryCB (const trajectory_msgs::JointTrajectoryConstPtr &msg)
 
bool send_to_robot (const std::vector< JointTrajPtMessage > &messages)
 
void streamingThread ()
 
virtual bool trajectory_to_msgs (const trajectory_msgs::JointTrajectoryConstPtr &traj, std::vector< JointTrajPtMessage > *msgs)
 
 ~FSRoboRJointTrajectoryStreamer ()
 
- Public Member Functions inherited from industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface
virtual bool init (std::string default_ip="", int default_port=StandardSocketPorts::MOTION)
 
virtual bool init (SmplMsgConnection *connection)
 
virtual bool init (SmplMsgConnection *connection, const std::vector< std::string > &joint_names, const std::map< std::string, double > &velocity_limits=std::map< std::string, double >())
 
 JointTrajectoryInterface ()
 
virtual void run ()
 
virtual ~JointTrajectoryInterface ()
 

Protected Member Functions

bool executeRobotProgramCB (fsrobo_r_msgs::ExecuteRobotProgram::Request &req, fsrobo_r_msgs::ExecuteRobotProgram::Response &res)
 
void trajectoryStop ()
 
- Protected Member Functions inherited from industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface
virtual bool calc_duration (const trajectory_msgs::JointTrajectoryPoint &pt, double *rbt_duration)
 
virtual bool calc_speed (const trajectory_msgs::JointTrajectoryPoint &pt, double *rbt_velocity, double *rbt_duration)
 
virtual bool calc_velocity (const trajectory_msgs::JointTrajectoryPoint &pt, double *rbt_velocity)
 
virtual bool is_valid (const trajectory_msgs::JointTrajectory &traj)
 
virtual void jointStateCB (const sensor_msgs::JointStateConstPtr &msg)
 
virtual bool select (const std::vector< std::string > &ros_joint_names, const trajectory_msgs::JointTrajectoryPoint &ros_pt, const std::vector< std::string > &rbt_joint_names, trajectory_msgs::JointTrajectoryPoint *rbt_pt)
 
virtual bool send_to_robot (const std::vector< JointTrajPtMessage > &messages)=0
 
virtual bool stopMotionCB (industrial_msgs::StopMotion::Request &req, industrial_msgs::StopMotion::Response &res)
 
virtual bool trajectory_to_msgs (const trajectory_msgs::JointTrajectoryConstPtr &traj, std::vector< JointTrajPtMessage > *msgs)
 
virtual bool transform (const trajectory_msgs::JointTrajectoryPoint &pt_in, trajectory_msgs::JointTrajectoryPoint *pt_out)
 

Protected Attributes

int current_point_
 
std::vector< JointTrajPtMessagecurrent_traj_
 
int min_buffer_size_
 
boost::mutex mutex_
 
RobotProgramExecutor robot_program_executor_
 
ros::ServiceServer srv_execute_robot_program
 
TransferState state_
 
ros::Time streaming_start_
 
boost::thread * streaming_thread_
 
- Protected Attributes inherited from industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface
std::vector< std::string > all_joint_names_
 
SmplMsgConnection * connection_
 
sensor_msgs::JointState cur_joint_pos_
 
double default_duration_
 
double default_joint_pos_
 
TcpClient default_tcp_connection_
 
double default_vel_ratio_
 
std::map< std::string, double > joint_vel_limits_
 
ros::NodeHandle node_
 
ros::ServiceServer srv_joint_trajectory_
 
ros::ServiceServer srv_stop_motion_
 
ros::Subscriber sub_cur_pos_
 
ros::Subscriber sub_joint_trajectory_
 

Detailed Description

Definition at line 67 of file fsrobo_r_joint_trajectory_streamer.h.

Constructor & Destructor Documentation

fsrobo_r_driver::joint_trajectory_streamer::FSRoboRJointTrajectoryStreamer::FSRoboRJointTrajectoryStreamer ( int  min_buffer_size = 1)
inline

Default constructor.

Parameters
min_buffer_sizeminimum number of points as required by robot implementation

Definition at line 78 of file fsrobo_r_joint_trajectory_streamer.h.

fsrobo_r_driver::joint_trajectory_streamer::FSRoboRJointTrajectoryStreamer::~FSRoboRJointTrajectoryStreamer ( )

Definition at line 58 of file fsrobo_r_joint_trajectory_streamer.cpp.

Member Function Documentation

bool fsrobo_r_driver::joint_trajectory_streamer::FSRoboRJointTrajectoryStreamer::executeRobotProgramCB ( fsrobo_r_msgs::ExecuteRobotProgram::Request &  req,
fsrobo_r_msgs::ExecuteRobotProgram::Response &  res 
)
protected

Definition at line 244 of file fsrobo_r_joint_trajectory_streamer.cpp.

bool fsrobo_r_driver::joint_trajectory_streamer::FSRoboRJointTrajectoryStreamer::init ( SmplMsgConnection connection,
const std::vector< std::string > &  joint_names,
const std::map< std::string, double > &  velocity_limits = std::map<std::string, double>() 
)
virtual

Class initializer.

Parameters
connectionsimple message connection that will be used to send commands to robot (ALREADY INITIALIZED)
joint_nameslist of expected joint-names.
  • Count and order should match data sent to robot connection.
  • Use blank-name to insert a placeholder joint position (typ. 0.0).
  • Joints in the incoming JointTrajectory stream that are NOT listed here will be ignored.
velocity_limitsmap of maximum velocities for each joint
  • leave empty to lookup from URDF
Returns
true on success, false otherwise (an invalid message type)

Definition at line 36 of file fsrobo_r_joint_trajectory_streamer.cpp.

void fsrobo_r_driver::joint_trajectory_streamer::FSRoboRJointTrajectoryStreamer::jointTrajectoryCB ( const trajectory_msgs::JointTrajectoryConstPtr &  msg)
virtual
bool fsrobo_r_driver::joint_trajectory_streamer::FSRoboRJointTrajectoryStreamer::send_to_robot ( const std::vector< JointTrajPtMessage > &  messages)

Definition at line 117 of file fsrobo_r_joint_trajectory_streamer.cpp.

void fsrobo_r_driver::joint_trajectory_streamer::FSRoboRJointTrajectoryStreamer::streamingThread ( )

Definition at line 150 of file fsrobo_r_joint_trajectory_streamer.cpp.

bool fsrobo_r_driver::joint_trajectory_streamer::FSRoboRJointTrajectoryStreamer::trajectory_to_msgs ( const trajectory_msgs::JointTrajectoryConstPtr &  traj,
std::vector< JointTrajPtMessage > *  msgs 
)
virtual

Definition at line 133 of file fsrobo_r_joint_trajectory_streamer.cpp.

void fsrobo_r_driver::joint_trajectory_streamer::FSRoboRJointTrajectoryStreamer::trajectoryStop ( )
protectedvirtual

Member Data Documentation

int fsrobo_r_driver::joint_trajectory_streamer::FSRoboRJointTrajectoryStreamer::current_point_
protected

Definition at line 110 of file fsrobo_r_joint_trajectory_streamer.h.

std::vector<JointTrajPtMessage> fsrobo_r_driver::joint_trajectory_streamer::FSRoboRJointTrajectoryStreamer::current_traj_
protected

Definition at line 111 of file fsrobo_r_joint_trajectory_streamer.h.

int fsrobo_r_driver::joint_trajectory_streamer::FSRoboRJointTrajectoryStreamer::min_buffer_size_
protected

Definition at line 114 of file fsrobo_r_joint_trajectory_streamer.h.

boost::mutex fsrobo_r_driver::joint_trajectory_streamer::FSRoboRJointTrajectoryStreamer::mutex_
protected

Definition at line 109 of file fsrobo_r_joint_trajectory_streamer.h.

RobotProgramExecutor fsrobo_r_driver::joint_trajectory_streamer::FSRoboRJointTrajectoryStreamer::robot_program_executor_
protected

Definition at line 117 of file fsrobo_r_joint_trajectory_streamer.h.

ros::ServiceServer fsrobo_r_driver::joint_trajectory_streamer::FSRoboRJointTrajectoryStreamer::srv_execute_robot_program
protected

Definition at line 116 of file fsrobo_r_joint_trajectory_streamer.h.

TransferState fsrobo_r_driver::joint_trajectory_streamer::FSRoboRJointTrajectoryStreamer::state_
protected

Definition at line 112 of file fsrobo_r_joint_trajectory_streamer.h.

ros::Time fsrobo_r_driver::joint_trajectory_streamer::FSRoboRJointTrajectoryStreamer::streaming_start_
protected

Definition at line 113 of file fsrobo_r_joint_trajectory_streamer.h.

boost::thread* fsrobo_r_driver::joint_trajectory_streamer::FSRoboRJointTrajectoryStreamer::streaming_thread_
protected

Definition at line 108 of file fsrobo_r_joint_trajectory_streamer.h.


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


fsrobo_r_driver
Author(s): F-ROSROBO
autogenerated on Sun Feb 9 2020 03:58:29