diff --git a/cfg/SafeCmd.cfg b/cfg/SafeCmd.cfg index 0b16418a6a33df1eafd78e6432d5d706509aa6f2..33d3535fe2aee429be9d84238ac92d4538dea9a9 100755 --- a/cfg/SafeCmd.cfg +++ b/cfg/SafeCmd.cfg @@ -39,7 +39,8 @@ gen = ParameterGenerator() ackermann = gen.add_group("ackermann") # Name Type Reconfiguration level Description Default Min Max -gen.add("safety_distance", double_t, 0, "Safety distance to possible obstacles",0.5, 0.0, 2.0) +gen.add("rate", double_t, 0, "Main loop rate (Hz)", 10.0, 0.1, 1000.0) +gen.add("safety_distance", double_t, 0, "Safety distance to possible obstacles",0.5, 0.0, 10.0) gen.add("traj_sim_distance", double_t, 0, "Distance for the trajectory computation", 1.0, 0.1, 5.0) gen.add("traj_sim_time", double_t, 0, "Time for the trajectory computation", 1.0, 0.1, 5.0) gen.add("traj_sim_step", double_t, 0, "Distance/Time increment for the trajectory computation", 0.1, 0.01, 0.5) diff --git a/param/sample.yaml b/param/sample.yaml index 8523c2182b8fba49278d020c5566f6ff862633a7..ec265351f1668320d99ae8c346acc84fb61b609a 100644 --- a/param/sample.yaml +++ b/param/sample.yaml @@ -1,3 +1,4 @@ +rate: 10 footprint: [[0.7,0.15],[0.7,-0.15],[-0.35,-0.15],[-0.35,0.15]] safety_distance: 0.2 traj_sim_distance: 2.0 diff --git a/src/safe_cmd_alg_node.cpp b/src/safe_cmd_alg_node.cpp index 893a89c721f6d1dab531245e9504609408e04053..d7ff4580cc50cdd1ebcc5e6fa120a382d78f221b 100644 --- a/src/safe_cmd_alg_node.cpp +++ b/src/safe_cmd_alg_node.cpp @@ -12,7 +12,12 @@ SafeCmdAlgNode::SafeCmdAlgNode(void) : tf2_listener(tf2_buffer) { //init class attributes if necessary - this->setRate(30);//in [Hz] + if(!this->private_node_handle_.getParam("rate", this->config.rate)) + { + ROS_WARN("SafeCmdAlgNode::SafeCmdAlgNode: param 'rate' not found"); + } + else + this->setRate(this->config.rate); // [init publishers] this->collision_points_publisher_ = this->private_node_handle_.advertise<sensor_msgs::PointCloud2>("collision_points", 1);