35 #include <rclcpp/exceptions/exceptions.hpp>
36 #include <rclcpp/logging.hpp>
37 #include <rclcpp/node.hpp>
38 #include <rclcpp/parameter_value.hpp>
43 static const std::string PARAM_CARTESIAN_LIMITS_NS =
"cartesian_limits";
45 static const std::string PARAM_MAX_TRANS_VEL =
"max_trans_vel";
46 static const std::string PARAM_MAX_TRANS_ACC =
"max_trans_acc";
47 static const std::string PARAM_MAX_TRANS_DEC =
"max_trans_dec";
48 static const std::string PARAM_MAX_ROT_VEL =
"max_rot_vel";
49 static const std::string PARAM_MAX_ROT_ACC =
"max_rot_acc";
50 static const std::string PARAM_MAX_ROT_DEC =
"max_rot_dec";
53 bool declareAndGetParam(
double& output_value,
const std::string& param_name,
const rclcpp::Node::SharedPtr& node)
57 if (!node->has_parameter(param_name))
59 node->declare_parameter<
double>(param_name, std::numeric_limits<double>::quiet_NaN());
61 node->get_parameter<
double>(param_name, output_value);
62 if (std::isnan(output_value))
64 RCLCPP_ERROR(node->get_logger(),
"Parameter \'%s\', is not set in the config file.", param_name.c_str());
69 catch (
const rclcpp::exceptions::InvalidParameterTypeException& e)
71 RCLCPP_WARN(node->get_logger(),
"InvalidParameterTypeException(\'%s\'): %s", param_name.c_str(), e.what());
72 RCLCPP_ERROR(node->get_logger(),
"Error getting parameter \'%s\', check parameter type in YAML file",
80 const std::string& param_namespace)
82 std::string param_prefix = param_namespace +
"." + PARAM_CARTESIAN_LIMITS_NS +
".";
101 double max_trans_dec;
116 if (node->has_parameter(param_prefix + PARAM_MAX_ROT_ACC) || node->has_parameter(param_prefix + PARAM_MAX_ROT_DEC))
118 RCLCPP_WARN(node->get_logger(),
119 "Ignoring cartesian limits parameters for rotational acceleration / deceleration; these parameters are "
120 "deprecated and are automatically calculated from translational to rotational ratio.");
124 return cartesian_limit;
bool declareAndGetParam(double &output_value, const std::string ¶m_name, const rclcpp::Node::SharedPtr &node)
Set of cartesian limits, has values for velocity, acceleration and deceleration of both the translati...
void setMaxRotationalVelocity(double max_rot_vel)
Set the maximum rotational velocity.
void setMaxTranslationalVelocity(double max_trans_vel)
Set the maximal translational velocity.
void setMaxTranslationalAcceleration(double max_trans_acc)
Set the maximum translational acceleration.
void setMaxTranslationalDeceleration(double max_trans_dec)
Set the maximum translational deceleration.
static CartesianLimit getAggregatedLimits(const rclcpp::Node::SharedPtr &node, const std::string ¶m_namespace)
Loads cartesian limits from the node parameters.