joint_limits_urdf.h
Go to the documentation of this file.
00001 
00002 // Copyright (C) 2013, PAL Robotics S.L.
00003 //
00004 // Redistribution and use in source and binary forms, with or without
00005 // modification, are permitted provided that the following conditions are met:
00006 //   * Redistributions of source code must retain the above copyright notice,
00007 //     this list of conditions and the following disclaimer.
00008 //   * Redistributions in binary form must reproduce the above copyright
00009 //     notice, this list of conditions and the following disclaimer in the
00010 //     documentation and/or other materials provided with the distribution.
00011 //   * Neither the name of PAL Robotics S.L. nor the names of its
00012 //     contributors may be used to endorse or promote products derived from
00013 //     this software without specific prior written permission.
00014 //
00015 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00016 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00017 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00018 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00019 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00020 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00021 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00022 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00023 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00024 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00025 // POSSIBILITY OF SUCH DAMAGE.
00027 
00029 
00030 #ifndef JOINT_LIMITS_INTERFACE_JOINT_LIMITS_URDF_H
00031 #define JOINT_LIMITS_INTERFACE_JOINT_LIMITS_URDF_H
00032 
00033 #include <ros/common.h>
00034 #if ROS_VERSION_MINIMUM(1, 9, 0) // TODO: Deprecate this conditional when Fuerte support is EOL'd
00035   #include <urdf_model/joint.h> // Fuerte.
00036 #else
00037   #include <urdf_interface/joint.h> // Groovy and later
00038 #endif
00039 #include <joint_limits_interface/joint_limits.h>
00040 
00041 namespace joint_limits_interface
00042 {
00043 
00051 inline bool getJointLimits(boost::shared_ptr<const urdf::Joint> urdf_joint, JointLimits& limits)
00052 {
00053   if (!urdf_joint || !urdf_joint->limits)
00054   {
00055     return false;
00056   }
00057 
00058   limits.has_position_limits = urdf_joint->type == urdf::Joint::REVOLUTE || urdf_joint->type == urdf::Joint::PRISMATIC;
00059   if (limits.has_position_limits)
00060   {
00061     limits.min_position = urdf_joint->limits->lower;
00062     limits.max_position = urdf_joint->limits->upper;
00063   }
00064 
00065   if (!limits.has_position_limits && urdf_joint->type == urdf::Joint::CONTINUOUS)
00066   {
00067     limits.angle_wraparound = true;
00068   }
00069 
00070   limits.has_velocity_limits = true;
00071   limits.max_velocity = urdf_joint->limits->velocity;
00072 
00073   limits.has_acceleration_limits = false;
00074 
00075   limits.has_effort_limits = true;
00076   limits.max_effort = urdf_joint->limits->effort;
00077 
00078   return true;
00079 }
00080 
00087 inline bool getSoftJointLimits(boost::shared_ptr<const urdf::Joint> urdf_joint, SoftJointLimits& soft_limits)
00088 {
00089   if (!urdf_joint || !urdf_joint->safety)
00090   {
00091     return false;
00092   }
00093 
00094   soft_limits.min_position = urdf_joint->safety->soft_lower_limit;
00095   soft_limits.max_position = urdf_joint->safety->soft_upper_limit;
00096   soft_limits.k_position = urdf_joint->safety->k_position;
00097   soft_limits.k_velocity = urdf_joint->safety->k_velocity;
00098 
00099   return true;
00100 }
00101 
00102 }
00103 
00104 #endif


joint_limits_interface
Author(s): Adolfo Rodriguez Tsouroukdissian
autogenerated on Thu Dec 1 2016 03:46:06