38 std::string config_file_path;
41 +
"/KNI_4.3.0/configfiles450/katana6M90A_G.cfg");
48 if (!n.
getParam(
"katana_joints", joint_names))
65 ROS_ERROR(
"Array of joint names should contain all strings. (namespace: %s)",
74 std::string robot_desc_string;
75 if (!n.
getParam(
"robot_description", robot_desc_string)) {
76 ROS_FATAL(
"Couldn't get a robot_description from the param server");
97 bool success = config.
openFile(config_file_path.c_str());
100 ROS_ERROR(
"Could not open config file: %s", config_file_path.c_str());
116 moveit_msgs::GetPositionFK::Response &res)
118 std::vector<double> jointAngles, coordinates;
120 if (req.fk_link_names.size() != 1 || req.fk_link_names[0] !=
"katana_gripper_tool_frame")
122 ROS_ERROR(
"The KNI kinematics solver can only solve requests for katana_gripper_tool_frame!");
128 std::vector<int> lookup =
makeJointsLookup(req.robot_state.joint_state.name);
129 if (lookup.size() == 0)
134 jointAngles.push_back(req.robot_state.joint_state.position[lookup[i]]);
139 geometry_msgs::PoseStamped pose_in, pose_out;
141 pose_in.header.frame_id =
"katana_base_frame";
144 pose_in.pose.position.x = coordinates[0];
145 pose_in.pose.position.y = coordinates[1];
146 pose_in.pose.position.z = coordinates[2];
171 res.pose_stamped.push_back(pose_out);
172 res.fk_link_names = req.fk_link_names;
173 res.error_code.val = res.error_code.SUCCESS;
179 moveit_msgs::GetPositionIK::Response &res)
181 std::vector<double> kni_coordinates(6, 0.0);
183 std::vector<int> seed_encoders(
NUM_JOINTS + 1);
185 if (req.ik_request.ik_link_name !=
"katana_gripper_tool_frame")
187 ROS_ERROR(
"The KNI kinematics solver can only solve requests for katana_gripper_tool_frame!");
192 std::vector<int> lookup =
makeJointsLookup(req.ik_request.robot_state.joint_state.name);
193 if (lookup.size() == 0)
202 geometry_msgs::PoseStamped pose_out;
205 bool success =
tf_listener_.
waitForTransform(
"katana_base_frame", req.ik_request.pose_stamped.header.frame_id, req.ik_request.pose_stamped.header.stamp,
235 ikBase_.
IKCalculate(kni_coordinates[0], kni_coordinates[1], kni_coordinates[2], kni_coordinates[3],
236 kni_coordinates[4], kni_coordinates[5], solution.begin(), seed_encoders);
240 res.error_code.val = res.error_code.NO_IK_SOLUTION;
247 res.solution.joint_state.position.resize(
NUM_JOINTS);
252 res.error_code.val = res.error_code.SUCCESS;
262 for (
size_t k = 0; k < joint_names.size(); ++k)
274 return std::vector<int>();
289 std::vector<double> result(6, 0.0);
290 std::vector<double>
pose(6, 0.0);
292 for (
size_t i = 0; i < jointAngles.size(); i++)
309 int main(
int argc,
char** argv)
311 ros::init(argc, argv,
"katana_arm_kinematics");
bool get_position_fk(moveit_msgs::GetPositionFK::Request &req, moveit_msgs::GetPositionFK::Response &res)
URDF_EXPORT bool initString(const std::string &xmlstring)
bool openFile(const char *filepath)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
Type const & getType() const
ROSCPP_DECL void spin(Spinner &spinner)
bool get_position_ik(moveit_msgs::GetPositionIK::Request &req, moveit_msgs::GetPositionIK::Response &res)
ros::ServiceServer get_fk_server_
double angle_rad2enc(int index, double angle)
static void quaternionMsgToTF(const geometry_msgs::Quaternion &msg, Quaternion &bt)
void getRPY(tfScalar &roll, tfScalar &pitch, tfScalar &yaw, unsigned int solution_number=1) const
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
double angle_enc2rad(int index, int encoders)
const std::string & getNamespace() const
tf::TransformListener tf_listener_
std::vector< std::string > joint_names_
void getCoordinatesFromEncoders(std::vector< double > &pose, const std::vector< int > &encs)
ROSLIB_DECL std::string getPath(const std::string &package_name)
void create(const char *configurationFile, CCplBase *protocol)
KNIConverter * converter_
ros::ServiceServer get_ik_server_
bool getParam(const std::string &key, std::string &s) const
static geometry_msgs::Quaternion createQuaternionMsgFromRollPitchYaw(double roll, double pitch, double yaw)
void IKCalculate(double X, double Y, double Z, double Al, double Be, double Ga, std::vector< int >::iterator solution_iter)
const size_t NUM_JOINTS
The number of joints in the katana (= only the 5 "real" joints)
std::vector< double > getCoordinates()
static const double KNI_TO_ROS_LENGTH
the conversion factor from KNI coordinates (in mm) to ROS coordinates (in m)
std::vector< int > encoders
std::vector< moveit_msgs::JointLimits > joint_limits_
std::vector< int > makeJointsLookup(std::vector< std::string > &joint_names)
copied from joint_trajectory_action_controller