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
00039 #include <moveit_sim_controller/moveit_sim_hw_interface.h>
00040
00041
00042 #include <rosparam_shortcuts/rosparam_shortcuts.h>
00043
00044 namespace moveit_sim_controller
00045 {
00046 MoveItSimHWInterface::MoveItSimHWInterface(ros::NodeHandle& nh, urdf::Model* urdf_model)
00047 : ros_control_boilerplate::SimHWInterface(nh, urdf_model), name_("moveit_sim_hw_interface")
00048 {
00049
00050 ros::NodeHandle rpnh(nh_, name_);
00051 std::size_t error = 0;
00052 error += !rosparam_shortcuts::get(name_, rpnh, "joint_model_group", joint_model_group_);
00053 error += !rosparam_shortcuts::get(name_, rpnh, "joint_model_group_pose", joint_model_group_pose_);
00054 rosparam_shortcuts::shutdownIfError(name_, error);
00055 }
00056
00057 void MoveItSimHWInterface::init()
00058 {
00059
00060 SimHWInterface::init();
00061
00062
00063 robot_model_loader_.reset(new robot_model_loader::RobotModelLoader(ROBOT_DESCRIPTION));
00064
00065
00066 loadDefaultJointValues();
00067
00068 ROS_INFO_STREAM_NAMED(name_, "MoveItSimHWInterface Ready.");
00069 }
00070
00071 void MoveItSimHWInterface::loadDefaultJointValues()
00072 {
00073
00074 robot_model::RobotModelPtr robot_model = robot_model_loader_->getModel();
00075
00076 if (!robot_model->hasJointModelGroup(joint_model_group_))
00077 {
00078 ROS_WARN_STREAM_NAMED(name_, "Unable to find joint model group " << joint_model_group_ << " for the fake "
00079 "controller manager");
00080 return;
00081 }
00082
00083 moveit::core::JointModelGroup* jmg = robot_model->getJointModelGroup(joint_model_group_);
00084
00085
00086 moveit::core::RobotState robot_state(robot_model);
00087
00088
00089 if (!robot_state.setToDefaultValues(jmg, joint_model_group_pose_))
00090 {
00091 ROS_WARN_STREAM_NAMED(name_, "Unable to find pose " << joint_model_group_pose_ << " for the fake controller "
00092 "manager");
00093 return;
00094 }
00095
00096 ROS_INFO_STREAM_NAMED(name_, "Set joints to pose " << joint_model_group_pose_);
00097
00098 for (std::size_t i = 0; i < joint_names_.size(); ++i)
00099 {
00100 const moveit::core::JointModel* jm = robot_state.getJointModel(joint_names_[i]);
00101
00102
00103 if (!jm)
00104 {
00105 ROS_WARN_STREAM_NAMED(name_, "Unable to find joint model group: " << joint_names_[i]);
00106 continue;
00107 }
00108 if (jm->getVariableCount() != 1)
00109 {
00110 ROS_WARN_STREAM_NAMED(name_, "Fake joint controller does not currently accept more than 1 "
00111 "variable per joint");
00112 continue;
00113 }
00114
00115
00116 joint_position_[i] = robot_state.getJointPositions(jm)[0];
00117 joint_position_command_[i] = robot_state.getJointPositions(jm)[0];
00118 }
00119 }
00120
00121 }