41 using JointTrajectoryDownloader::init;
46 bool init(std::string default_ip =
"",
int default_port = StandardSocketPorts::MOTION)
48 if (!JointTrajectoryDownloader::init(default_ip, default_port))
59 bool transform(
const trajectory_msgs::JointTrajectoryPoint& pt_in, trajectory_msgs::JointTrajectoryPoint* pt_out)
68 bool calc_velocity(
const trajectory_msgs::JointTrajectoryPoint& pt,
double* rbt_velocity)
75 int main(
int argc,
char** argv)
78 ros::init(argc, argv,
"motion_interface");
82 motionInterface.
init();
83 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.
bool init(std::string default_ip="", int default_port=StandardSocketPorts::MOTION)
ROSCPP_DECL bool get(const std::string &key, std::string &s)
ROSCPP_DECL bool has(const std::string &key)
int main(int argc, char **argv)
bool calc_velocity(const trajectory_msgs::JointTrajectoryPoint &pt, double *rbt_velocity)
bool transform(const trajectory_msgs::JointTrajectoryPoint &pt_in, trajectory_msgs::JointTrajectoryPoint *pt_out)