Skip to content

Commit 7b0de66

Browse files
committed
initial dgps build
1 parent 7ee96ed commit 7b0de66

16 files changed

Lines changed: 259 additions & 67 deletions

docker/Dockerfile

Lines changed: 7 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
FROM osrf/ros:humble-desktop-full
1+
FROM osrf/ros:jazzy-desktop-full
22

33
ARG DEBIAN_FRONTEND=noninteractive
44

@@ -20,7 +20,8 @@ RUN apt-get update \
2020

2121
# add a user
2222
ARG user_id
23-
ARG USER jammy
23+
ARG USER noble
24+
RUN userdel ubuntu
2425
RUN useradd -U --uid ${user_id} -ms /bin/bash $USER \
2526
&& echo "$USER:$USER" | chpasswd \
2627
&& adduser $USER sudo \
@@ -32,20 +33,20 @@ WORKDIR /home/$USER
3233

3334
# imu driver
3435
RUN sudo apt-get update \
35-
&& sudo apt-get install -y ros-humble-gtsam
36+
&& sudo apt-get install -y ros-jazzy-gtsam
3637

3738
RUN sudo apt-get install -y python3-colcon-common-extensions
3839

3940
# install visualizer deps
40-
RUN sudo apt-get install -y python3-pip
41-
RUN pip3 install flask folium flask_socketio utm
41+
#RUN sudo apt-get install -y python3-pip
42+
#RUN pip3 install flask folium flask_socketio utm
4243
RUN sudo apt install -y libgoogle-glog-dev
4344
# build ros env
4445
RUN mkdir ws
4546

4647
# make life nice inside docker
4748
RUN sudo chown $USER:$USER ~/.bashrc \
48-
&& /bin/sh -c 'echo ". /opt/ros/humble/setup.bash" >> ~/.bashrc' \
49+
&& /bin/sh -c 'echo ". /opt/ros/jazzy/setup.bash" >> ~/.bashrc' \
4950
&& /bin/sh -c 'echo "source ~/ws/install/setup.bash" >> ~/.bashrc' \
5051
&& echo 'export PS1="\[$(tput setaf 2; tput bold)\]\u\[$(tput setaf 7)\]@\[$(tput setaf 3)\]\h\[$(tput setaf 7)\]:\[$(tput setaf 4)\]\W\[$(tput setaf 7)\]$ \[$(tput sgr0)\]"' >> ~/.bashrc
5152

docker/Dockerfile.humble

Lines changed: 50 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,50 @@
1+
FROM osrf/ros:humble-desktop-full
2+
3+
ARG DEBIAN_FRONTEND=noninteractive
4+
5+
# install the basics
6+
RUN apt-get update \
7+
&& apt-get install -y --no-install-recommends \
8+
vim \
9+
tmux \
10+
cmake \
11+
gcc \
12+
g++ \
13+
git \
14+
build-essential \
15+
sudo \
16+
wget \
17+
curl \
18+
zip \
19+
unzip
20+
21+
# add a user
22+
ARG user_id
23+
ARG USER jammy
24+
RUN useradd -U --uid ${user_id} -ms /bin/bash $USER \
25+
&& echo "$USER:$USER" | chpasswd \
26+
&& adduser $USER sudo \
27+
&& echo "$USER ALL=NOPASSWD: ALL" >> /etc/sudoers.d/$USER
28+
29+
# add groups to get access to sensors
30+
USER $USER
31+
WORKDIR /home/$USER
32+
33+
# imu driver
34+
RUN sudo apt-get update \
35+
&& sudo apt-get install -y ros-humble-gtsam
36+
37+
RUN sudo apt-get install -y python3-colcon-common-extensions
38+
39+
# install visualizer deps
40+
RUN sudo apt-get install -y python3-pip
41+
RUN pip3 install flask folium flask_socketio utm
42+
RUN sudo apt install -y libgoogle-glog-dev
43+
# build ros env
44+
RUN mkdir ws
45+
46+
# make life nice inside docker
47+
RUN sudo chown $USER:$USER ~/.bashrc \
48+
&& /bin/sh -c 'echo ". /opt/ros/humble/setup.bash" >> ~/.bashrc' \
49+
&& /bin/sh -c 'echo "source ~/ws/install/setup.bash" >> ~/.bashrc' \
50+
&& echo 'export PS1="\[$(tput setaf 2; tput bold)\]\u\[$(tput setaf 7)\]@\[$(tput setaf 3)\]\h\[$(tput setaf 7)\]:\[$(tput setaf 4)\]\W\[$(tput setaf 7)\]$ \[$(tput sgr0)\]"' >> ~/.bashrc

docker/build-jazzy.bash

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,3 @@
1+
#!/bin/bash
2+
3+
docker build --build-arg user_id=$(id -u) --build-arg USER=$(whoami) --build-arg NAME=$(hostname) --rm -t glider-ros:jazzy .

docker/run.bash renamed to docker/run-jazzy.bash

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -7,11 +7,11 @@ docker run -it --rm \
77
-v "/dev:/dev" \
88
-v "/tmp/.X11-unix:/tmp/.X11-unix" \
99
-v "`pwd`/../glider:/home/`whoami`/ws/src/glider" \
10-
-v "/home/`whoami`/Data/evmapper:/home/`whoami`/data" \
10+
-v "/home/`whoami`/Data:/home/`whoami`/data" \
1111
-e DISPLAY=$DISPLAY \
1212
-e QT_X11_NO_MITSHM=1 \
1313
-e XAUTHORITY=$XAUTH \
14-
--name glider-ros-humble \
15-
glider-ros:humble \
14+
--name glider-ros-jazzy \
15+
glider-ros:jazzy \
1616
bash
1717
xhost -

glider/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -58,6 +58,7 @@ include_directories(
5858
add_library(${PROJECT_NAME} SHARED
5959
src/parameters.cpp
6060
src/time.cpp
61+
src/gps_heading.cpp
6162
src/odometry.cpp
6263
src/odometry_with_covariance.cpp
6364
src/factor_manager.cpp

glider/config/graph-params.yaml

Lines changed: 15 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -1,17 +1,22 @@
1-
covariances:
2-
accelerometer: 0.00001
3-
gyroscope: 0.00001
4-
integration: 0.001
5-
heading: 0.09
6-
roll_pitch: 0.001
7-
bias: 0.001
8-
gps: 2.0
1+
imu:
2+
covariances:
3+
accelerometer: 0.00001
4+
gyroscope: 0.00001
5+
integration: 0.001
6+
heading: 0.09
7+
roll_pitch: 0.001
8+
bias: 0.001
9+
frame: "enu"
10+
gps:
11+
covariance: 2.0
12+
dgpsfm:
13+
enable: false
14+
integration_threshold: 1.0
15+
covariance: 0.03
916
constants:
1017
gravity: 9.81
1118
bias_num_measurements: 100
1219
initial_num_measurements: 4
13-
frame:
14-
imu: "enu"
1520
logging:
1621
stdout: true
1722
optimizer:

glider/include/glider/core/factor_manager.hpp

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -79,6 +79,13 @@ class FactorManager
7979
* @param timestamp: time of the gps measurement
8080
* @param gps: GPS measurement in the UTM frame */
8181
void addGpsFactor(int64_t timestamp, const Eigen::Vector3d& gps);
82+
/*! @brief adds the gps measurement and a heading from dgps
83+
* @param timestamp: time of the gps measurement
84+
* @param gps: GPS measurement in the UTM frame
85+
* @param heading: heading from dgpsfm in the ENU frame
86+
* @param fuse: whether or not to add the heading measurement
87+
* to the factor graph */
88+
void addGpsFactor(int64_t timestamp, const Eigen::Vector3d& gps, const double& heading, const bool fuse);
8289
/*! @brief adds the imu measurements to the pim and saves the orientation
8390
* @param timestamp: time of the imu measurement
8491
* @param accel: the accelerometer reading
@@ -165,6 +172,8 @@ class FactorManager
165172
gtsam::noiseModel::Isotropic::shared_ptr gps_noise_;
166173
// @brief noise in the orientation estimate from the imu
167174
gtsam::noiseModel::Base::shared_ptr orient_noise_;
175+
// @brief noise in the heading estimate of differential gps
176+
gtsam::noiseModel::Base::shared_ptr dgpsfm_noise_;
168177

169178
// factor graph
170179
// @brief tracks the number of times the optimizer has been called

glider/include/glider/core/glider.hpp

Lines changed: 11 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@
1313
#include <glog/logging.h>
1414

1515
#include "glider/core/factor_manager.hpp"
16+
#include "glider/utils/gps_heading.hpp"
1617
#include "glider/utils/geodetics.hpp"
1718

1819
namespace Glider
@@ -69,5 +70,15 @@ class Glider
6970
// @brief the relative translation from the gps to
7071
// the imu
7172
Eigen::Vector3d t_imu_gps_;
73+
// @brief whether or not to use differential gps
74+
// from motion for heading
75+
bool use_dgpsfm_;
76+
// @brief save the state estimate from
77+
// the optimizer
78+
OdometryWithCovariance current_odom_;
79+
// @brief save the previous gps measurement for
80+
// dgpsfm
81+
Eigen::Vector3d last_gps_;
82+
double vel_threshold_;
7283
};
7384
}

glider/include/glider/utils/gps_heading.hpp

Lines changed: 3 additions & 31 deletions
Original file line numberDiff line numberDiff line change
@@ -23,45 +23,17 @@ namespace geodetics
2323
* @param lon2: the TO longitude in degrees decimal
2424
* @return heading_rad: the heading in radians in the NED frame
2525
*/
26-
double gpsHeading(double lat1, double lon1, double lat2, double lon2)
27-
{
28-
double lat1_rad = lat1 * M_PI / 180.0;
29-
double lon1_rad = lon1 * M_PI / 180.0;
30-
double lat2_rad = lat2 * M_PI / 180.0;
31-
double lon2_rad = lon2 * M_PI / 180.0;
32-
33-
double lon_diff = lon2_rad - lon1_rad;
34-
35-
double y = std::sin(lon_diff) * std::cos(lat2_rad);
36-
double x = std::cos(lat1_rad) * std::sin(lat2_rad) - std::sin(lat1_rad) * std::cos(lat2_rad) * std::cos(lon_diff);
37-
38-
double heading_rad = std::atan2(y,x);
39-
40-
return heading_rad;
41-
}
42-
26+
double gpsHeading(double lat1, double lon1, double lat2, double lon2);
4327
/*! @brief convert a heading in radians to degrees and normalize to [0,360)
4428
* @param heading: the heading in radians, can be ENU or NED frame
4529
* @return heading_deg: normalized heading in degrees in the same frame
4630
* that was input
4731
*/
48-
double headingRadiansToDegrees(double heading)
49-
{
50-
double heading_deg = heading * (180.0 / M_PI);
51-
52-
heading_deg = std::fmod(std::fmod(heading_deg, 360.0) + 360.0, 360.0);
53-
return heading_deg;
54-
}
55-
32+
double headingRadiansToDegrees(double heading);
5633
/*! @brief convert a heading from the geodetic frame (NED) to the ENU frame
5734
* @param geodetic_heading: heading in radians in the geodetic (NED) frame
5835
* @return enu_heading: heading in radians in the ENU frame
5936
*/
60-
double geodeticToENU(double geodetic_heading)
61-
{
62-
double enu_heading = std::fmod((M_PI/2 - geodetic_heading + (2*M_PI)), (2*M_PI));
63-
64-
return enu_heading;
65-
}
37+
double geodeticToENU(double geodetic_heading);
6638
} // namespace geodetics
6739
} // namespace glider

0 commit comments

Comments
 (0)