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 #include <iostream>
00031 #include <map>
00032 #include <memory>
00033 #include <string>
00034
00035 #include <ros/init.h>
00036
00037 #include <xpp_hyq/inverse_kinematics_hyq4.h>
00038 #include <xpp_msgs/topic_names.h>
00039 #include <xpp_states/joints.h>
00040 #include <xpp_states/endeffector_mappings.h>
00041
00042 #include <xpp_vis/cartesian_joint_converter.h>
00043 #include <xpp_vis/urdf_visualizer.h>
00044
00045 using namespace xpp;
00046 using namespace quad;
00047
00048 int main(int argc, char *argv[])
00049 {
00050 ::ros::init(argc, argv, "hyq_urdf_visualizer");
00051
00052 const std::string joint_desired_hyq = "xpp/joint_hyq_des";
00053
00054 auto hyq_ik = std::make_shared<InverseKinematicsHyq4>();
00055 CartesianJointConverter inv_kin_converter(hyq_ik,
00056 xpp_msgs::robot_state_desired,
00057 joint_desired_hyq);
00058
00059
00060 int n_ee = hyq_ik->GetEECount();
00061 int n_j = HyqlegJointCount;
00062 std::vector<UrdfVisualizer::URDFName> joint_names(n_ee*n_j);
00063 joint_names.at(n_j*LF + HAA) = "lf_haa_joint";
00064 joint_names.at(n_j*LF + HFE) = "lf_hfe_joint";
00065 joint_names.at(n_j*LF + KFE) = "lf_kfe_joint";
00066 joint_names.at(n_j*RF + HAA) = "rf_haa_joint";
00067 joint_names.at(n_j*RF + HFE) = "rf_hfe_joint";
00068 joint_names.at(n_j*RF + KFE) = "rf_kfe_joint";
00069 joint_names.at(n_j*LH + HAA) = "lh_haa_joint";
00070 joint_names.at(n_j*LH + HFE) = "lh_hfe_joint";
00071 joint_names.at(n_j*LH + KFE) = "lh_kfe_joint";
00072 joint_names.at(n_j*RH + HAA) = "rh_haa_joint";
00073 joint_names.at(n_j*RH + HFE) = "rh_hfe_joint";
00074 joint_names.at(n_j*RH + KFE) = "rh_kfe_joint";
00075
00076 std::string urdf = "hyq_rviz_urdf_robot_description";
00077 UrdfVisualizer hyq_desired(urdf, joint_names, "base", "world",
00078 joint_desired_hyq, "hyq_des");
00079
00080 ::ros::spin();
00081
00082 return 1;
00083 }
00084