-
Notifications
You must be signed in to change notification settings - Fork 168
Expand file tree
/
Copy pathangular_velocity_offset_stop_node.cpp
More file actions
114 lines (100 loc) · 5.5 KB
/
angular_velocity_offset_stop_node.cpp
File metadata and controls
114 lines (100 loc) · 5.5 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
// Copyright (c) 2019, Map IV, Inc.
// All rights reserved.
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
// * Redistributions of source code must retain the above copyright notice,
// this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above copyright notice,
// this list of conditions and the following disclaimer in the documentation
// and/or other materials provided with the distribution.
// * Neither the name of the Map IV, Inc. nor the names of its contributors
// may be used to endorse or promote products derived from this software
// without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
// DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDER BE LIABLE FOR ANY
// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
/*
* angular_velocity_offset_stop.cpp
* Author MapIV Sekino
*/
#include "rclcpp/rclcpp.hpp"
#include "eagleye_coordinate/eagleye_coordinate.hpp"
#include "eagleye_navigation/eagleye_navigation.hpp"
class AngularVelocityOffsetStopNode : public rclcpp::Node
{
public:
AngularVelocityOffsetStopNode() : Node("eagleye_angular_velocity_offset_stop")
{
std::string subscribe_twist_topic_name = "vehicle/twist";
std::string yaml_file;
this->declare_parameter("yaml_file", yaml_file);
this->get_parameter("yaml_file", yaml_file);
std::cout << "yaml_file: " << yaml_file << std::endl;
try
{
YAML::Node conf = YAML::LoadFile(yaml_file);
angular_velocity_offset_stop_parameter_.imu_rate = conf["/**"]["ros__parameters"]["common"]["imu_rate"].as<double>();
angular_velocity_offset_stop_parameter_.stop_judgment_threshold = conf["/**"]["ros__parameters"]["common"]["stop_judgment_threshold"].as<double>();
angular_velocity_offset_stop_parameter_.estimated_interval = conf["/**"]["ros__parameters"]["angular_velocity_offset_stop"]["estimated_interval"].as<double>();
angular_velocity_offset_stop_parameter_.outlier_threshold = conf["/**"]["ros__parameters"]["angular_velocity_offset_stop"]["outlier_threshold"].as<double>();
std::cout << "subscribe_twist_topic_name " << subscribe_twist_topic_name << std::endl;
std::cout << "imu_rate " << angular_velocity_offset_stop_parameter_.imu_rate << std::endl;
std::cout << "stop_judgment_threshold " << angular_velocity_offset_stop_parameter_.stop_judgment_threshold << std::endl;
std::cout << "estimated_minimum_interval " << angular_velocity_offset_stop_parameter_.estimated_interval << std::endl;
std::cout << "outlier_threshold " << angular_velocity_offset_stop_parameter_.outlier_threshold << std::endl;
}
catch (YAML::Exception& e)
{
std::cerr << "\033[1;31mangular_velocity_offset_stop Node YAML Error: " << e.msg << "\033[0m" << std::endl;
exit(3);
}
sub1_ = this->create_subscription<geometry_msgs::msg::TwistStamped>(
subscribe_twist_topic_name, 1000,
std::bind(&AngularVelocityOffsetStopNode::velocityCallback, this, std::placeholders::_1));
sub2_ = this->create_subscription<sensor_msgs::msg::Imu>(
"imu/data_tf_converted", 1000,
std::bind(&AngularVelocityOffsetStopNode::imuCallback, this, std::placeholders::_1));
pub_ = this->create_publisher<eagleye_msgs::msg::AngularVelocityOffset>("angular_velocity_offset_stop", 1000);
}
private:
geometry_msgs::msg::TwistStamped velocity_;
eagleye_msgs::msg::AngularVelocityOffset angular_velocity_offset_stop_;
sensor_msgs::msg::Imu imu_;
struct AngularVelocityOffsetStopParameter angular_velocity_offset_stop_parameter_;
struct AngularVelocityOffsetStopStatus angular_velocity_offset_stop_status_ = {};
rclcpp::Subscription<geometry_msgs::msg::TwistStamped>::SharedPtr sub1_;
rclcpp::Subscription<sensor_msgs::msg::Imu>::SharedPtr sub2_;
rclcpp::Publisher<eagleye_msgs::msg::AngularVelocityOffset>::SharedPtr pub_;
void velocityCallback(const geometry_msgs::msg::TwistStamped::ConstSharedPtr msg)
{
velocity_ = *msg;
}
void imuCallback(const sensor_msgs::msg::Imu::ConstSharedPtr msg)
{
imu_.header = msg->header;
imu_.orientation = msg->orientation;
imu_.orientation_covariance = msg->orientation_covariance;
imu_.angular_velocity = msg->angular_velocity;
imu_.angular_velocity_covariance = msg->angular_velocity_covariance;
imu_.linear_acceleration = msg->linear_acceleration;
imu_.linear_acceleration_covariance = msg->linear_acceleration_covariance;
angular_velocity_offset_stop_.header = msg->header;
angular_velocity_offset_stop_estimate(velocity_, imu_, angular_velocity_offset_stop_parameter_, &angular_velocity_offset_stop_status_, &angular_velocity_offset_stop_);
pub_->publish(angular_velocity_offset_stop_);
}
};
int main(int argc, char** argv)
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<AngularVelocityOffsetStopNode>());
return 0;
}