moveit_sim_hw_interface.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2015, University of Colorado, Boulder
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the Univ of CO, Boulder nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 /* Author: Dave Coleman <dave@dav.ee>
00036    Desc:   Simulates a robot using ros_control controllers with a default position loaded from MoveIt!
00037 */
00038 
00039 #include <moveit_sim_controller/moveit_sim_hw_interface.h>
00040 
00041 // ROS parameter loading
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   // Load rosparams
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   // Call parent class version of this function
00060   SimHWInterface::init();
00061 
00062   // Load the loader
00063   robot_model_loader_.reset(new robot_model_loader::RobotModelLoader(ROBOT_DESCRIPTION));
00064 
00065   // Load default joint values
00066   loadDefaultJointValues();
00067 
00068   ROS_INFO_STREAM_NAMED(name_, "MoveItSimHWInterface Ready.");
00069 }
00070 
00071 void MoveItSimHWInterface::loadDefaultJointValues()
00072 {
00073   // Load the robot model
00074   robot_model::RobotModelPtr robot_model = robot_model_loader_->getModel();  // Get a shared pointer to the robot
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   // Load a robot state
00086   moveit::core::RobotState robot_state(robot_model);
00087 
00088   // Check for existance of joint model group
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     // Error check
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     // Set position from SRDF
00116     joint_position_[i] = robot_state.getJointPositions(jm)[0];
00117     joint_position_command_[i] = robot_state.getJointPositions(jm)[0];
00118   }
00119 }
00120 
00121 }  // namespace moveit_sim_controller


moveit_sim_controller
Author(s): Dave Coleman
autogenerated on Thu Jun 6 2019 19:11:45