Go to the documentation of this file.
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)
std::vector< std::string > get_joint_names()
void add_handler(MessageHandler *handler, bool allow_replace=true)
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ROSCPP_DECL bool get(const std::string &key, bool &b)
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 getJointNames(const std::string joint_list_param, const std::string urdf_param, std::vector< std::string > &joint_names)
bool transform(const std::vector< double > &pos_in, std::vector< double > *pos_out)
bool init(SmplMsgConnection *connection)
ROSCPP_DECL bool has(const std::string &key)
int main(int argc, char **argv)
virtual ~Fanuc_JointRelayHandler()
Fanuc_JointRelayHandler()
SmplMsgConnection * get_connection()
bool init(industrial::smpl_msg_connection::SmplMsgConnection *connection, std::vector< std::string > &joint_names)
fanuc_driver
Author(s): G.A. vd. Hoorn (TU Delft Robotics Institute)
autogenerated on Thu Feb 20 2025 04:09:12