Skip to content

Commit 9dad0f1

Browse files
committed
system/mrm_comfortable_stop_operator
Signed-off-by: karishma <karishma@interpl.ai>
1 parent 8e209a1 commit 9dad0f1

File tree

2 files changed

+49
-4
lines changed

2 files changed

+49
-4
lines changed
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,45 @@
1+
{
2+
"$schema": "http://json-schema.org/draft-07/schema#",
3+
"title": "Parameters for mrm_comfortable_stop_operator",
4+
"type": "object",
5+
"definitions": {
6+
"velodyne_monitor": {
7+
"type": "object",
8+
"properties": {
9+
"update_rate": {
10+
"type": "number",
11+
"default": 10,
12+
"description": "Timer callback frequency [Hz]."
13+
},
14+
"min_acceleration": {
15+
"type": "number",
16+
"default": -1.0,
17+
"description": "Minimum acceleration for comfortable stop [m/s^2]."
18+
},
19+
"max_jerk": {
20+
"type": "number",
21+
"default": 0.3,
22+
"description": "Maximum jerk for comfortable stop [m/s^3]."
23+
},
24+
"min_jerk": {
25+
"type": "number",
26+
"default": -0.3,
27+
"description": "Minimum jerk for comfortable stop [m/s^3]."
28+
}
29+
},
30+
"required": ["update_rate", "min_acceleration", "max_jerk", "min_jerk"]
31+
}
32+
},
33+
"properties": {
34+
"/**": {
35+
"type": "object",
36+
"properties": {
37+
"ros__parameters": {
38+
"$ref": "#/definitions/mrm_comfortable_stop_operator"
39+
}
40+
},
41+
"required": ["ros__parameters"]
42+
}
43+
},
44+
"required": ["/**"]
45+
}

system/mrm_comfortable_stop_operator/src/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -21,10 +21,10 @@ MrmComfortableStopOperator::MrmComfortableStopOperator(const rclcpp::NodeOptions
2121
: Node("mrm_comfortable_stop_operator", node_options)
2222
{
2323
// Parameter
24-
params_.update_rate = static_cast<int>(declare_parameter<int>("update_rate", 1));
25-
params_.min_acceleration = declare_parameter<double>("min_acceleration", -1.0);
26-
params_.max_jerk = declare_parameter<double>("max_jerk", 0.3);
27-
params_.min_jerk = declare_parameter<double>("min_jerk", 0.3);
24+
params_.update_rate = static_cast<int>(declare_parameter<int>("update_rate"));
25+
params_.min_acceleration = declare_parameter<double>("min_acceleration");
26+
params_.max_jerk = declare_parameter<double>("max_jerk");
27+
params_.min_jerk = declare_parameter<double>("min_jerk");
2828

2929
// Server
3030
service_operation_ = create_service<tier4_system_msgs::srv::OperateMrm>(

0 commit comments

Comments
 (0)