File tree 10 files changed +20
-14
lines changed
launch/tier4_localization_launch/launch/pose_twist_fusion_filter
localization/autoware_twist2accel
10 files changed +20
-14
lines changed Original file line number Diff line number Diff line change @@ -93,7 +93,7 @@ localization/pose2twist/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masah
93
93
localization /pose_estimator_arbiter /** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
94
94
localization /pose_initializer /** anh.nguyen.2@tier4.jp isamu.takagi@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
95
95
localization /pose_instability_detector /** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
96
- localization /twist2accel /** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
96
+ localization /autoware_twist2accel /** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
97
97
localization /yabloc /yabloc_common /** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
98
98
localization /yabloc /yabloc_image_processing /** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
99
99
localization /yabloc /yabloc_monitor /** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
Original file line number Diff line number Diff line change 26
26
</group >
27
27
28
28
<group >
29
- <include file =" $(find-pkg-share twist2accel )/launch/twist2accel.launch.xml" >
29
+ <include file =" $(find-pkg-share autoware_twist2accel )/launch/twist2accel.launch.xml" >
30
30
<arg name =" in_odom" value =" /localization/kinematic_state" />
31
31
<arg name =" in_twist" value =" /localization/twist_estimator/twist_with_covariance" />
32
32
<arg name =" out_accel" value =" /localization/acceleration" />
Original file line number Diff line number Diff line change 1
1
cmake_minimum_required (VERSION 3.14)
2
- project (twist2accel )
2
+ project (autoware_twist2accel )
3
3
4
4
find_package (autoware_cmake REQUIRED)
5
5
autoware_package()
@@ -9,7 +9,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED
9
9
)
10
10
11
11
rclcpp_components_register_node(${PROJECT_NAME}
12
- PLUGIN "Twist2Accel"
12
+ PLUGIN "autoware::twist2accel:: Twist2Accel"
13
13
EXECUTABLE ${PROJECT_NAME} _node
14
14
EXECUTOR SingleThreadedExecutor
15
15
)
Original file line number Diff line number Diff line change 1
- # twist2accel
1
+ # autoware_twist2accel
2
2
3
3
## Purpose
4
4
@@ -21,7 +21,7 @@ This package is responsible for estimating acceleration using the output of `ekf
21
21
22
22
## Parameters
23
23
24
- {{ json_to_markdown("localization/twist2accel /schema/twist2accel.schema.json") }}
24
+ {{ json_to_markdown("localization/autoware_twist2accel /schema/twist2accel.schema.json") }}
25
25
26
26
## Future work
27
27
File renamed without changes.
Original file line number Diff line number Diff line change 1
1
<launch >
2
- <arg name =" param_file" default =" $(find-pkg-share twist2accel )/config/twist2accel.param.yaml" />
2
+ <arg name =" param_file" default =" $(find-pkg-share autoware_twist2accel )/config/twist2accel.param.yaml" />
3
3
4
4
<arg name =" in_odom" default =" in_odom" />
5
5
<arg name =" in_twist" default =" in_twist" />
6
6
<arg name =" out_accel" default =" out_accel" />
7
- <node pkg =" twist2accel " exec =" twist2accel_node " output =" both" >
7
+ <node pkg =" autoware_twist2accel " exec =" autoware_twist2accel_node " output =" both" >
8
8
<remap from =" input/odom" to =" $(var in_odom)" />
9
9
<remap from =" input/twist" to =" $(var in_twist)" />
10
10
<remap from =" output/accel" to =" $(var out_accel)" />
Original file line number Diff line number Diff line change 1
1
<?xml version =" 1.0" ?>
2
2
<?xml-model href =" http://download.ros.org/schema/package_format3.xsd" schematypens =" http://www.w3.org/2001/XMLSchema" ?>
3
3
<package format =" 3" >
4
- <name >twist2accel </name >
4
+ <name >autoware_twist2accel </name >
5
5
<version >0.0.0</version >
6
6
<description >The acceleration estimation package</description >
7
7
<maintainer email =" yamato.ando@tier4.jp" >Yamato Ando</maintainer >
File renamed without changes.
Original file line number Diff line number Diff line change 12
12
// See the License for the specific language governing permissions and
13
13
// limitations under the License.
14
14
15
- #include " twist2accel/twist2accel .hpp"
15
+ #include " twist2accel.hpp"
16
16
17
17
#include < rclcpp/logging.hpp>
18
18
22
22
#include < string>
23
23
#include < utility>
24
24
25
+ namespace autoware ::twist2accel
26
+ {
25
27
using std::placeholders::_1;
26
28
27
29
Twist2Accel::Twist2Accel (const rclcpp::NodeOptions & node_options)
@@ -103,6 +105,7 @@ void Twist2Accel::estimate_accel(const geometry_msgs::msg::TwistStamped::SharedP
103
105
pub_accel_->publish (accel_msg);
104
106
prev_twist_ptr_ = msg;
105
107
}
108
+ } // namespace autoware::twist2accel
106
109
107
110
#include < rclcpp_components/register_node_macro.hpp>
108
- RCLCPP_COMPONENTS_REGISTER_NODE (Twist2Accel)
111
+ RCLCPP_COMPONENTS_REGISTER_NODE (autoware::twist2accel:: Twist2Accel)
Original file line number Diff line number Diff line change 12
12
// See the License for the specific language governing permissions and
13
13
// limitations under the License.
14
14
15
- #ifndef TWIST2ACCEL__TWIST2ACCEL_HPP_
16
- #define TWIST2ACCEL__TWIST2ACCEL_HPP_
15
+ #ifndef TWIST2ACCEL_HPP_
16
+ #define TWIST2ACCEL_HPP_
17
17
18
18
#include " signal_processing/lowpass_filter_1d.hpp"
19
19
37
37
#include < string>
38
38
#include < vector>
39
39
40
+ namespace autoware ::twist2accel
41
+ {
40
42
class Twist2Accel : public rclcpp ::Node
41
43
{
42
44
public:
@@ -68,4 +70,5 @@ class Twist2Accel : public rclcpp::Node
68
70
void callback_odometry (const nav_msgs::msg::Odometry::SharedPtr msg);
69
71
void estimate_accel (const geometry_msgs::msg::TwistStamped::SharedPtr msg);
70
72
};
71
- #endif // TWIST2ACCEL__TWIST2ACCEL_HPP_
73
+ } // namespace autoware::twist2accel
74
+ #endif // TWIST2ACCEL_HPP_
You can’t perform that action at this time.
0 commit comments