#include <fsrobo_r_joint_trajectory_streamer.h>
|
| 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 () |
|
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 () |
|
|
bool | executeRobotProgramCB (fsrobo_r_msgs::ExecuteRobotProgram::Request &req, fsrobo_r_msgs::ExecuteRobotProgram::Response &res) |
|
void | trajectoryStop () |
|
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) |
|
fsrobo_r_driver::joint_trajectory_streamer::FSRoboRJointTrajectoryStreamer::FSRoboRJointTrajectoryStreamer |
( |
int |
min_buffer_size = 1 | ) |
|
|
inline |
fsrobo_r_driver::joint_trajectory_streamer::FSRoboRJointTrajectoryStreamer::~FSRoboRJointTrajectoryStreamer |
( |
| ) |
|
bool fsrobo_r_driver::joint_trajectory_streamer::FSRoboRJointTrajectoryStreamer::executeRobotProgramCB |
( |
fsrobo_r_msgs::ExecuteRobotProgram::Request & |
req, |
|
|
fsrobo_r_msgs::ExecuteRobotProgram::Response & |
res |
|
) |
| |
|
protected |
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
-
connection | simple message connection that will be used to send commands to robot (ALREADY INITIALIZED) |
joint_names | list 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_limits | map 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 | ) |
|
void fsrobo_r_driver::joint_trajectory_streamer::FSRoboRJointTrajectoryStreamer::streamingThread |
( |
| ) |
|
bool fsrobo_r_driver::joint_trajectory_streamer::FSRoboRJointTrajectoryStreamer::trajectory_to_msgs |
( |
const trajectory_msgs::JointTrajectoryConstPtr & |
traj, |
|
|
std::vector< JointTrajPtMessage > * |
msgs |
|
) |
| |
|
virtual |
void fsrobo_r_driver::joint_trajectory_streamer::FSRoboRJointTrajectoryStreamer::trajectoryStop |
( |
| ) |
|
|
protectedvirtual |
int fsrobo_r_driver::joint_trajectory_streamer::FSRoboRJointTrajectoryStreamer::current_point_ |
|
protected |
std::vector<JointTrajPtMessage> fsrobo_r_driver::joint_trajectory_streamer::FSRoboRJointTrajectoryStreamer::current_traj_ |
|
protected |
int fsrobo_r_driver::joint_trajectory_streamer::FSRoboRJointTrajectoryStreamer::min_buffer_size_ |
|
protected |
boost::mutex fsrobo_r_driver::joint_trajectory_streamer::FSRoboRJointTrajectoryStreamer::mutex_ |
|
protected |
RobotProgramExecutor fsrobo_r_driver::joint_trajectory_streamer::FSRoboRJointTrajectoryStreamer::robot_program_executor_ |
|
protected |
ros::ServiceServer fsrobo_r_driver::joint_trajectory_streamer::FSRoboRJointTrajectoryStreamer::srv_execute_robot_program |
|
protected |
TransferState fsrobo_r_driver::joint_trajectory_streamer::FSRoboRJointTrajectoryStreamer::state_ |
|
protected |
ros::Time fsrobo_r_driver::joint_trajectory_streamer::FSRoboRJointTrajectoryStreamer::streaming_start_ |
|
protected |
boost::thread* fsrobo_r_driver::joint_trajectory_streamer::FSRoboRJointTrajectoryStreamer::streaming_thread_ |
|
protected |
The documentation for this class was generated from the following files: