Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 #include <ros/ros.h>
00039
00040
00041 #include <moveit/robot_model_loader/robot_model_loader.h>
00042 #include <moveit/robot_model/robot_model.h>
00043 #include <moveit/robot_state/robot_state.h>
00044 #include <moveit/robot_state/joint_state_group.h>
00045
00046 int main(int argc, char **argv)
00047 {
00048 ros::init (argc, argv, "right_arm_kinematics");
00049 ros::AsyncSpinner spinner(1);
00050 spinner.start();
00051
00052
00053 robot_model_loader::RobotModelLoader robot_model_loader("robot_description");
00054
00055
00056 robot_model::RobotModelPtr kinematic_model = robot_model_loader.getModel();
00057
00058
00059 ROS_INFO("Model frame: %s", kinematic_model->getModelFrame().c_str());
00060
00061
00062
00063 robot_state::RobotStatePtr kinematic_state(new robot_state::RobotState(kinematic_model));
00064
00065
00066 kinematic_state->setToDefaultValues();
00067
00068
00069 robot_state::JointStateGroup* joint_state_group = kinematic_state->getJointStateGroup("right_arm");
00070
00071
00072 const std::vector<std::string> &joint_names = joint_state_group->getJointModelGroup()->getJointModelNames();
00073
00074
00075 std::vector<double> joint_values;
00076 joint_state_group->getVariableValues(joint_values);
00077
00078
00079 for(std::size_t i = 0; i < joint_names.size(); ++i)
00080 {
00081 ROS_INFO("Joint %s: %f", joint_names[i].c_str(), joint_values[i]);
00082 }
00083
00084
00085 joint_values[0] = 1.57;
00086 joint_state_group->setVariableValues(joint_values);
00087
00088
00089 ROS_INFO_STREAM("Current state is " << (kinematic_state->satisfiesBounds() ? "valid" : "not valid"));
00090
00091
00092 kinematic_state->enforceBounds();
00093 ROS_INFO_STREAM("Current state is " << (kinematic_state->satisfiesBounds() ? "valid" : "not valid"));
00094
00095
00096
00097 joint_state_group->setToRandomValues();
00098 const Eigen::Affine3d &end_effector_state = joint_state_group->getRobotState()->getLinkState("r_wrist_roll_link")->getGlobalLinkTransform();
00099
00100
00101 ROS_INFO_STREAM("Translation: " << end_effector_state.translation());
00102 ROS_INFO_STREAM("Rotation: " << end_effector_state.rotation());
00103
00104
00105
00106 joint_state_group->setToRandomValues();
00107
00108
00109
00110
00111
00112 bool found_ik = joint_state_group->setFromIK(end_effector_state, 10, 0.1);
00113
00114
00115 if (found_ik)
00116 {
00117 joint_state_group->getVariableValues(joint_values);
00118 for(std::size_t i=0; i < joint_names.size(); ++i)
00119 {
00120 ROS_INFO("Joint %s: %f", joint_names[i].c_str(), joint_values[i]);
00121 }
00122 }
00123 else
00124 {
00125 ROS_INFO("Did not find IK solution");
00126 }
00127
00128
00129
00130 Eigen::Vector3d reference_point_position(0.0,0.0,0.0);
00131 Eigen::MatrixXd jacobian;
00132 joint_state_group->getJacobian(joint_state_group->getJointModelGroup()->getLinkModelNames().back(),
00133 reference_point_position,
00134 jacobian);
00135 ROS_INFO_STREAM("Jacobian: " << jacobian);
00136
00137 ros::shutdown();
00138 return 0;
00139 }