rrbot_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
00036    Desc:   Example ros_control hardware interface blank template for the RRBot
00037            For a more detailed simulation example, see sim_hw_interface.cpp
00038 */
00039 
00040 #include <rrbot_control/rrbot_hw_interface.h>
00041 
00042 namespace rrbot_control
00043 {
00044 
00045 RRBotHWInterface::RRBotHWInterface(ros::NodeHandle &nh, urdf::Model *urdf_model)
00046   : ros_control_boilerplate::GenericHWInterface(nh, urdf_model)
00047 {
00048   ROS_INFO_NAMED("rrbot_hw_interface", "RRBotHWInterface Ready.");
00049 }
00050 
00051 void RRBotHWInterface::read(ros::Duration &elapsed_time)
00052 {
00053   // ----------------------------------------------------
00054   // ----------------------------------------------------
00055   // ----------------------------------------------------
00056   //
00057   // FILL IN YOUR READ COMMAND FROM USB/ETHERNET/ETHERCAT/SERIAL ETC HERE
00058   //
00059   // ----------------------------------------------------
00060   // ----------------------------------------------------
00061   // ----------------------------------------------------
00062 }
00063 
00064 void RRBotHWInterface::write(ros::Duration &elapsed_time)
00065 {
00066   // Safety
00067   enforceLimits(elapsed_time);
00068 
00069   // ----------------------------------------------------
00070   // ----------------------------------------------------
00071   // ----------------------------------------------------
00072   //
00073   // FILL IN YOUR WRITE COMMAND TO USB/ETHERNET/ETHERCAT/SERIAL ETC HERE
00074   //
00075   // FOR A EASY SIMULATION EXAMPLE, OR FOR CODE TO CALCULATE
00076   // VELOCITY FROM POSITION WITH SMOOTHING, SEE
00077   // sim_hw_interface.cpp IN THIS PACKAGE
00078   //
00079   // DUMMY PASS-THROUGH CODE
00080   for (std::size_t joint_id = 0; joint_id < num_joints_; ++joint_id)
00081     joint_position_[joint_id] += joint_position_command_[joint_id];
00082   // END DUMMY CODE
00083   //
00084   // ----------------------------------------------------
00085   // ----------------------------------------------------
00086   // ----------------------------------------------------
00087 }
00088 
00089 void RRBotHWInterface::enforceLimits(ros::Duration &period)
00090 {
00091   // ----------------------------------------------------
00092   // ----------------------------------------------------
00093   // ----------------------------------------------------
00094   //
00095   // CHOOSE THE TYPE OF JOINT LIMITS INTERFACE YOU WANT TO USE
00096   // YOU SHOULD ONLY NEED TO USE ONE SATURATION INTERFACE,
00097   // DEPENDING ON YOUR CONTROL METHOD
00098   //
00099   // EXAMPLES:
00100   //
00101   // Saturation Limits ---------------------------
00102   //
00103   // Enforces position and velocity
00104   pos_jnt_sat_interface_.enforceLimits(period);
00105   //
00106   // Enforces velocity and acceleration limits
00107   // vel_jnt_sat_interface_.enforceLimits(period);
00108   //
00109   // Enforces position, velocity, and effort
00110   // eff_jnt_sat_interface_.enforceLimits(period);
00111 
00112   // Soft limits ---------------------------------
00113   //
00114   // pos_jnt_soft_limits_.enforceLimits(period);
00115   // vel_jnt_soft_limits_.enforceLimits(period);
00116   // eff_jnt_soft_limits_.enforceLimits(period);
00117   //
00118   // ----------------------------------------------------
00119   // ----------------------------------------------------
00120   // ----------------------------------------------------
00121 }
00122 
00123 }  // namespace


ros_control_boilerplate
Author(s): Dave Coleman
autogenerated on Thu Jun 6 2019 20:37:19