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 #include <moveit/robot_model/joint_model.h>
00038 #include <moveit/robot_model/link_model.h>
00039
00040 robot_model::JointModel::JointModel(const std::string& name) :
00041 name_(name), type_(UNKNOWN), max_velocity_(0.0), parent_link_model_(NULL), child_link_model_(NULL),
00042 mimic_(NULL), mimic_factor_(1.0), mimic_offset_(0.0), passive_(false), distance_factor_(1.0), tree_index_(-1)
00043 {
00044 }
00045
00046 robot_model::JointModel::~JointModel()
00047 {
00048 }
00049
00050 bool robot_model::JointModel::getVariableBounds(const std::string& variable, std::pair<double, double>& bounds) const
00051 {
00052 std::map<std::string, unsigned int>::const_iterator it = variable_index_.find(variable);
00053 if (it == variable_index_.end())
00054 {
00055 logWarn("Could not find variable '%s' to get bounds for within joint '%s'", variable.c_str(), name_.c_str());
00056 return false;
00057 }
00058 bounds = variable_bounds_[it->second];
00059 return true;
00060 }
00061
00062 bool robot_model::JointModel::setVariableBounds(const std::string& variable, const std::pair<double, double>& bounds)
00063 {
00064 std::map<std::string, unsigned int>::const_iterator it = variable_index_.find(variable);
00065 if (it == variable_index_.end())
00066 {
00067 logWarn("Could not find variable '%s' to set bounds for within joint '%s'", variable.c_str(), name_.c_str());
00068 return false;
00069 }
00070 variable_bounds_[it->second] = bounds;
00071 return true;
00072 }
00073
00074 void robot_model::JointModel::getVariableDefaultValues(std::map<std::string, double> &values, const Bounds &bounds) const
00075 {
00076 std::vector<double> defv;
00077 defv.reserve(variable_names_.size());
00078 getVariableDefaultValues(defv, bounds);
00079 for (std::size_t i = 0 ; i < variable_names_.size() ; ++i)
00080 values[variable_names_[i]] = defv[i];
00081 }
00082
00083 void robot_model::JointModel::getVariableRandomValues(random_numbers::RandomNumberGenerator &rng, std::map<std::string, double> &values, const Bounds &bounds) const
00084 {
00085 std::vector<double> rv;
00086 rv.reserve(variable_names_.size());
00087 getVariableRandomValues(rng, rv, bounds);
00088 for (std::size_t i = 0 ; i < variable_names_.size() ; ++i)
00089 values[variable_names_[i]] = rv[i];
00090 }
00091
00092 void robot_model::JointModel::computeDefaultVariableLimits()
00093 {
00094 default_limits_.clear();
00095 for (std::size_t i = 0; i < variable_names_.size(); ++i)
00096 {
00097 moveit_msgs::JointLimits lim;
00098 lim.joint_name = variable_names_[i];
00099 lim.has_position_limits = true;
00100 lim.min_position = variable_bounds_[i].first;
00101 lim.max_position = variable_bounds_[i].second;
00102 if (max_velocity_ != 0.0)
00103 lim.has_velocity_limits = true;
00104 else
00105 lim.has_velocity_limits = false;
00106 lim.max_velocity = max_velocity_;
00107 lim.has_acceleration_limits = false;
00108 lim.max_acceleration = 0.0;
00109 default_limits_.push_back(lim);
00110 }
00111 }
00112
00113 void robot_model::JointModel::setVariableLimits(const std::vector<moveit_msgs::JointLimits>& jlim)
00114 {
00115 user_specified_limits_.clear();
00116 for (std::size_t j = 0; j < variable_names_.size(); ++j)
00117 for (std::size_t i = 0 ; i < jlim.size() ; ++i)
00118 if (jlim[i].joint_name == variable_names_[j])
00119 {
00120 user_specified_limits_.push_back(jlim[i]);
00121 break;
00122 }
00123 if (user_specified_limits_.size() > 0 && user_specified_limits_.size() != variable_names_.size())
00124 {
00125 logError("Incorrect number of joint limits was specified!");
00126 user_specified_limits_.clear();
00127 }
00128 }