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
00047 #include <moveit/robot_state/conversions.h>
00048 #include <moveit_msgs/DisplayRobotState.h>
00049
00050
00051 #include <boost/math/constants/constants.hpp>
00052
00053
00054
00055
00056
00057
00058 int main(int argc, char **argv)
00059 {
00060 ros::init (argc, argv, "state_display_tutorial");
00061
00062
00063 ros::AsyncSpinner spinner(1);
00064 spinner.start();
00065
00066
00067 robot_model_loader::RobotModelLoader robot_model_loader("robot_description");
00068
00069
00070 robot_model::RobotModelPtr kinematic_model = robot_model_loader.getModel();
00071
00072
00073 robot_state::RobotStatePtr kinematic_state(new robot_state::RobotState(kinematic_model));
00074
00075
00076 robot_state::JointStateGroup* joint_state_group = kinematic_state->getJointStateGroup("right_arm");
00077
00078
00079
00080
00081 ros::NodeHandle nh;
00082 ros::Publisher robot_state_publisher = nh.advertise<moveit_msgs::DisplayRobotState>( "tutorial_robot_state", 1 );
00083
00084
00085 ros::Rate loop_rate(1);
00086
00087 for (int cnt=0; cnt<5 && ros::ok(); cnt++)
00088 {
00089 joint_state_group->setToRandomValues();
00090
00091
00092 moveit_msgs::DisplayRobotState msg;
00093 robot_state::robotStateToRobotStateMsg(*kinematic_state, msg.state);
00094
00095
00096 robot_state_publisher.publish( msg );
00097
00098
00099 ros::spinOnce();
00100 loop_rate.sleep();
00101 }
00102
00103
00104
00105
00106
00107
00108 kinematic_state->setToDefaultValues();
00109
00110 const Eigen::Affine3d end_effector_default_pose =
00111 kinematic_state->getLinkState("r_wrist_roll_link")->getGlobalLinkTransform();
00112
00113 const double PI = boost::math::constants::pi<double>();
00114 const double RADIUS = 0.1;
00115
00116 for (double angle=0; angle<=2*PI && ros::ok(); angle+=2*PI/20)
00117 {
00118
00119
00120 Eigen::Affine3d end_effector_pose =
00121 Eigen::Translation3d(RADIUS * cos(angle), RADIUS * sin(angle), 0.0) * end_effector_default_pose;
00122
00123 ROS_INFO_STREAM("End effector position:\n" << end_effector_pose.translation());
00124
00125
00126 bool found_ik = joint_state_group->setFromIK(end_effector_pose, 10, 0.1);
00127 if (!found_ik)
00128 {
00129 ROS_INFO_STREAM("Could not solve IK for pose\n" << end_effector_pose.translation());
00130 continue;
00131 }
00132
00133
00134 moveit_msgs::DisplayRobotState msg;
00135 robot_state::robotStateToRobotStateMsg(*kinematic_state, msg.state);
00136
00137
00138 robot_state_publisher.publish( msg );
00139
00140
00141 ros::spinOnce();
00142 loop_rate.sleep();
00143 }
00144
00145 ros::shutdown();
00146 return 0;
00147 }