Skip to content

Commit 7977e3e

Browse files
authored
Merge pull request #17 from KumarRobotics/bug/timing-logging
This PR fixes the hard coded logging issues. It also fixes timestamping when running with a bag file.
2 parents 04c725f + 59dc38a commit 7977e3e

File tree

6 files changed

+30
-28
lines changed

6 files changed

+30
-28
lines changed

README.md

Lines changed: 15 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,20 @@
66
Glider is a G-INS system built on [GTSAM](https://github.com/borglab/gtsam). It currently takes in GPS and 9-DOF IMU and provides a full
77
state estimate up to the rate of you IMU. Glider is designed to be configured to your system.
88

9+
## Building Glider
10+
Glider can be build with colcon as a ROS2 package with `colcon build --packages-select glider`. If you only want the api you can build with:
11+
```
12+
cmake -S . -B build -DBUILD_ROS=OFF
13+
cmake --build build
14+
```
15+
16+
## Running Glider
17+
To run glider with ros use `ros2 run glider glider-node.launch.py`. If you are running with a bag file use:
18+
```
19+
ros2 bag run <bag_file_name> --clock
20+
ros2 launch glider glider-node.launch.py use_sim_time:=true
21+
```
22+
923
## Hardware Setup
1024
You're setup needs a GPS and a 9-DOF IMU, that is an IMU that provides a full orientation. The IMU orientation should be provided in the IMU's frame
1125
as this is standard for robotics, but we are working on supporting the NED frame. We use a VectorNav VN100T IMU. It is important make sure your IMU magnetometer is calibrated, if it is not aligned correctly the heading output of glider will be incorrect.
@@ -18,7 +32,7 @@ the parameters mean:
1832
- `publishers.viz.use`: if true will publish an `Odometry` topic for visualization centered around the origin.
1933
- `publishers.viz.origin_easting`: the easting value you want to viz odometry to center around.
2034
- `publishers.viz.origin_northing`: the northing value you want the viz odometry to center around.
21-
- `subscribers.use_odom`: Still under development
35+
- `subscribers.use_odom`: Still under development.
2236

2337
## Glider Setup
2438
You can configure glider itself in `config/glider-params.yaml`, this is where you can specify the parameters for the factor graph. Here's more detail on each parameter:

glider/config/glider-params.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,7 @@ frame:
1414
imu: "enu"
1515
logging:
1616
stdout: true
17-
directory: "/home/jason/.ros/log/glider"
17+
directory: "/tmp/glider"
1818
optimizer:
1919
smooth: true
2020
lag_time: 5.0

glider/include/ros/glider_node.hpp

Lines changed: 0 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -71,19 +71,13 @@ class GliderNode : public rclcpp::Node
7171

7272
// parameters
7373
bool initialized_;
74-
bool use_sim_time_;
7574
bool publish_nsf_;
7675
bool viz_;
7776
std::string utm_zone_;
78-
double declination_;
7977
double origin_easting_;
8078
double origin_northing_;
81-
int gps_counter_;
82-
int gps_init_count_;
8379

8480
// tracker
8581
Glider::OdometryWithCovariance current_state_;
86-
87-
int64_t latest_imu_timestamp_;
8882
};
8983
}

glider/launch/glider-node.launch.py

Lines changed: 12 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -7,37 +7,30 @@
77
"""
88

99
import os
10+
import yaml
1011
from launch import LaunchDescription
1112
from launch.actions import DeclareLaunchArgument
1213
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
1314
from launch_ros.actions import Node
1415
from launch_ros.substitutions import FindPackageShare
16+
from ament_index_python.packages import get_package_share_directory
1517

1618

1719
def generate_launch_description():
18-
# create logging directory
19-
os.makedirs("/home/jason/.ros/log/glider", exist_ok=True)
20-
2120
# Declare launch arguments
2221
use_sim_time_arg = DeclareLaunchArgument(
2322
'use_sim_time',
2423
default_value='false',
2524
description='Use simulation time'
2625
)
2726

28-
use_odom_arg = DeclareLaunchArgument(
29-
'use_odom',
30-
default_value='false',
31-
description='Use odometry'
32-
)
33-
3427
# Get launch configurations
3528
use_sim_time = LaunchConfiguration('use_sim_time')
36-
use_odom = LaunchConfiguration('use_odom')
3729

3830
# Find package share directory
3931
glider_share = FindPackageShare('glider')
40-
32+
glider_share_dir = get_package_share_directory('glider')
33+
4134
# Path to parameter files
4235
ros_params_file = PathJoinSubstitution([
4336
glider_share,
@@ -50,7 +43,12 @@ def generate_launch_description():
5043
'config',
5144
'glider-params.yaml'
5245
])
53-
46+
47+
# create logging directory
48+
with open(os.path.join(glider_share_dir, "config", "glider-params.yaml")) as f:
49+
config = yaml.safe_load(f)
50+
os.makedirs(config["logging"]["directory"], exist_ok=True)
51+
5452
# Create the glider node
5553
glider_node = Node(
5654
package='glider',
@@ -61,7 +59,7 @@ def generate_launch_description():
6159
ros_params_file,
6260
{'path': graph_params_file,
6361
'use_sim_time': use_sim_time,
64-
'use_odom': use_odom}
62+
'use_odom': False}
6563
],
6664
remappings=[
6765
('/gps', '/ublox/fix'),
@@ -70,4 +68,4 @@ def generate_launch_description():
7068
]
7169
)
7270

73-
return LaunchDescription([use_sim_time_arg, use_odom_arg, glider_node])
71+
return LaunchDescription([use_sim_time_arg, glider_node])

glider/ros/glider_node.cpp

Lines changed: 0 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -31,9 +31,6 @@ GliderNode::GliderNode(const rclcpp::NodeOptions& options) : rclcpp::Node("glide
3131
bool use_odom = this->get_parameter("subscribers.use_odom").as_bool();
3232

3333
std::string path = this->get_parameter("path").as_string();
34-
use_sim_time_ = this->get_clock()->get_clock_type() == RCL_ROS_TIME;
35-
36-
latest_imu_timestamp_ = 0;
3734

3835
glider_ = std::make_unique<Glider::Glider>(path);
3936
current_state_ = Glider::OdometryWithCovariance::Uninitialized();
@@ -109,8 +106,6 @@ void GliderNode::imuCallback(const sensor_msgs::msg::Imu::ConstSharedPtr msg)
109106
int64_t timestamp = getTime(msg->header.stamp);
110107

111108
glider_->addImu(timestamp, accel, gyro, orient);
112-
113-
latest_imu_timestamp_ = timestamp;
114109
}
115110

116111
void GliderNode::gpsCallback(const sensor_msgs::msg::NavSatFix::ConstSharedPtr msg)

glider/src/glider.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -25,14 +25,15 @@ Glider::Glider(const std::string& path)
2525

2626
LOG(INFO) << "[GLIDER] Using IMU frame: " << frame_;
2727
LOG(INFO) << "[GLIDER] Using Fixed Lag Smoother: " << std::boolalpha << params.smooth;
28+
LOG(INFO) << "[GLIDER] Logging to: " << params.log_dir;
2829
LOG(INFO) << "[GLIDER] Glider initialized";
2930
}
3031

3132
void Glider::initializeLogging(const Parameters& params) const
3233
{
3334
// initialize GLog
3435
google::InitGoogleLogging("Glider");
35-
// TODO fix hard coding
36+
3637
FLAGS_log_dir = params.log_dir;
3738
if (params.log) FLAGS_alsologtostderr = 1;
3839
}

0 commit comments

Comments
 (0)