diff --git a/src/safe_cmd_alg_node.cpp b/src/safe_cmd_alg_node.cpp index 33106c092a8cc7280d962845048b96f2feeee900..30938ba503445761fc79b81d227cab9325c786d2 100644 --- a/src/safe_cmd_alg_node.cpp +++ b/src/safe_cmd_alg_node.cpp @@ -4,8 +4,8 @@ SafeCmdAlgNode::SafeCmdAlgNode(void) : algorithm_base::IriBaseAlgorithm<SafeCmdAlgorithm>(), collision_time_(1), min_dist_(0.3), - max_vel_front_(10), - max_vel_rear_(10) + max_vel_front_(1), + max_vel_rear_(-1) { //init class attributes if necessary loop_rate_ = 20;//in [Hz] @@ -143,7 +143,7 @@ int main(int argc,char *argv[]) float SafeCmdAlgNode::compute_max_velocity_(const sensor_msgs::LaserScan::ConstPtr& scan) const { - float max_velocity = 10; + float max_velocity = 1; for (uint i = 0; i < scan->ranges.size(); i++) {