62 ROS_FATAL(
"Joint 2-3 linkage factor parameter not supplied.");
63 throw std::runtime_error(
"Cannot find required parameter 'J23_factor' on parameter server.");
73 bool transform(
const std::vector<double>& pos_in, std::vector<double>* pos_out)
82 int main(
int argc,
char** argv)
bool init(std::string default_ip="", int default_port=StandardSocketPorts::STATE)
bool init(industrial::smpl_msg_connection::SmplMsgConnection *connection, std::vector< std::string > &joint_names)
bool getJointNames(const std::string joint_list_param, const std::string urdf_param, std::vector< std::string > &joint_names)
SmplMsgConnection * get_connection()
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 transform(const std::vector< double > &pos_in, std::vector< double > *pos_out)
ROSCPP_DECL bool get(const std::string &key, std::string &s)
void add_handler(MessageHandler *handler, bool allow_replace=true)
ROSCPP_DECL bool has(const std::string &key)
std::vector< std::string > get_joint_names()
virtual ~Fanuc_JointRelayHandler()
int main(int argc, char **argv)
Fanuc_JointRelayHandler()