59 ROS_FATAL(
"Joint 2-3 linkage factor parameter not supplied.");
60 throw std::runtime_error(
"Cannot find required parameter 'J23_factor' on parameter server.");
70 bool transform(
const trajectory_msgs::JointTrajectoryPoint& pt_in,
71 trajectory_msgs::JointTrajectoryPoint* pt_out)
81 int main(
int argc,
char** argv)
84 ros::init(argc, argv,
"motion_interface");
89 motionInterface.
init();
90 motionInterface.
run();
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void linkage_transform(const std::vector< double > &joints_in, std::vector< double > *joints_out, double J23_factor=0)
Corrects for parallel linkage coupling between joints.
ROSCPP_DECL bool get(const std::string &key, std::string &s)
virtual ~Fanuc_JointTrajectoryStreamer()
Fanuc_JointTrajectoryStreamer()
ROSCPP_DECL bool has(const std::string &key)
bool transform(const trajectory_msgs::JointTrajectoryPoint &pt_in, trajectory_msgs::JointTrajectoryPoint *pt_out)
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 >())
int main(int argc, char **argv)