Skip to content

Commit

Permalink
Fix style.sh, add venv to gitignore, update dockerfile, comment ansib…
Browse files Browse the repository at this point in the history
…le, make dev.yml perform sysstem upgrade, make ansible handle python virtualenv instead of bootstrap, specify versions exactly in pyproject, format some code in auton
  • Loading branch information
qhdwight committed Sep 18, 2023
1 parent 6f59ce0 commit 75749da
Show file tree
Hide file tree
Showing 15 changed files with 96 additions and 82 deletions.
5 changes: 4 additions & 1 deletion .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -32,4 +32,7 @@ logs/
moteus-cal*

# CSV
*.csv
*.csv

# Virtual Environment
venv/
25 changes: 9 additions & 16 deletions Dockerfile
Original file line number Diff line number Diff line change
@@ -1,33 +1,26 @@
FROM ros:noetic

RUN apt-get update && apt-get upgrade -y
# Add apt repo for latest version of Git
RUN apt-get install software-properties-common -y && add-apt-repository ppa:git-core/ppa -y
RUN apt-get update && apt-get install -y \
zsh neovim sudo git git-lfs \
clang-format-12 clang-tidy-12 \
python3-catkin-tools python3-pip
RUN DEBIAN_FRONTEND=noninteractive apt-get install keyboard-configuration -y
RUN apt-get update -y && apt-get upgrade -y && apt-get install software-properties-common -y
RUN apt-add-repository ppa:ansible/ansible -y
RUN apt-add-repository ppa:git-core/ppa -y
RUN apt install -y ansible git git-lfs

RUN useradd --create-home --groups sudo --shell /bin/zsh mrover
# Give mrover user sudo access with no password
RUN echo '%sudo ALL=(ALL) NOPASSWD:ALL' >> /etc/sudoers

USER mrover
RUN mkdir -p ~/catkin_ws/src/mrover
RUN mkdir -p /home/mrover/catkin_ws/src/mrover
WORKDIR /home/mrover/catkin_ws/src/mrover
# ROS package manager (rosdep) reads this file to install dependencies
ADD ./package.xml .
# Python package manager (pip) reads this file to install dependencies
ADD ./requirements.txt .
# Install ROS packages
RUN rosdep update && rosdep install --from-paths . --ignore-src -y --rosdistro=noetic
ADD ./pyproject.toml .
ADD ./ansible ./ansible
ADD ./ansible.sh .
RUN ./ansible.sh build.yml

USER root
# Remove apt cache to free up space in the image
RUN apt-get clean && rm -rf /var/lib/apt/lists/*
# Install Python packags, sudo so it is a global install
RUN pip3 install -r ./requirements.txt

USER mrover
ENTRYPOINT [ "/bin/zsh" ]
24 changes: 24 additions & 0 deletions ansible/roles/build/tasks/main.yml
Original file line number Diff line number Diff line change
@@ -1,8 +1,10 @@
# Allows us to install Python versions newer than 3.8
- name: Add Python PPA
become: True
apt_repository:
repo: ppa:deadsnakes/ppa

# Allows us to install G++11, so we can use an updated libstdc++ which provides more standard library features (C++20)
- name: Add GCC PPA
become: True
apt_repository:
Expand All @@ -13,6 +15,7 @@
apt_key:
url: https://apt.llvm.org/llvm-snapshot.gpg.key

# Allows us to install Clang 16 and other LLVM tools
- name: Add LLVM APT List
become: True
apt_repository:
Expand All @@ -25,6 +28,7 @@
url: https://apt.kitware.com/keys/kitware-archive-latest.asc
keyring: /usr/share/keyrings/kitware-archive-keyring.gpg

# Allows us to install CMake versions newer than 3.16
- name: Add CMake APT List
become: True
apt_repository:
Expand All @@ -42,6 +46,13 @@
repo: deb http://packages.ros.org/ros/ubuntu {{ ubuntu_release }} main
filename: ros

- name: Upgrade APT Packages
become: True
apt:
cache_valid_time: 604800
state: latest
upgrade: yes

- name: Install APT Packages
become: True
apt:
Expand All @@ -53,12 +64,16 @@
- neovim
- sudo
- cmake
# Caches intermediate build files, speeds up compilation over time
- ccache
# Faster than make
- ninja-build
- tmux
- zstd
- htop
- curl
- unzip
- rsync
- python3-pip
- python3-rosdep
- python3-catkin-tools
Expand All @@ -77,6 +92,7 @@
become: True
command: rosdep init
args:
# This command will be skipped if this file already exists
creates: /etc/ros/rosdep/sources.list.d/20-default.list

- name: Update rosdep
Expand Down Expand Up @@ -133,3 +149,11 @@
path: /usr/bin/clang-16
link: /usr/bin/clang
priority: 160

- name: Setup Python Virtual Environment
pip:
name:
# Installs from pyproject.toml
- "{{ catkin_workspace }}/src/mrover[dev]"
virtualenv: "{{ catkin_workspace }}/src/mrover/venv"
virtualenv_command: python3.10 -m venv
26 changes: 13 additions & 13 deletions pyproject.toml
Original file line number Diff line number Diff line change
Expand Up @@ -9,23 +9,23 @@ maintainers = [
{ name = "Michigan Mars Rover Team" }
]
dependencies = [
"django",
"empy",
"numpy",
"pandas",
"shapely",
"pyserial",
"moteus",
"pymap3d",
"aenum",
"pyyaml",
"rospkg",
"Django==4.2.5",
"empy==3.3.4",
"numpy==1.26.0",
"pandas==2.1.0",
"shapely==2.0.1",
"pyserial==3.5",
"moteus==0.3.59",
"pymap3d==3.0.1",
"aenum==3.1.15",
"PyYAML==6.0.1",
"rospkg==1.5.0",
]

[project.optional-dependencies]
dev = [
"black",
"mypy",
"black==23.9.1",
"mypy==1.5.1",
]

[project.urls]
Expand Down
Empty file added src/esw/__init__.py
Empty file.
3 changes: 0 additions & 3 deletions src/esw/brushless.py
Original file line number Diff line number Diff line change
Expand Up @@ -125,12 +125,10 @@ def is_mode_indicating_error(mode: int) -> bool:


class MoteusBridge:

MOTEUS_RESPONSE_TIME_INDICATING_DISCONNECTED_S = 0.01
ROVER_NODE_TO_MOTEUS_WATCHDOG_TIMEOUT_S = 0.1

def __init__(self, can_id: int, transport, gear_ratio: int):

self._can_id = can_id
self.controller = moteus.Controller(id=can_id, transport=transport)
self.command_lock = threading.Lock()
Expand Down Expand Up @@ -369,7 +367,6 @@ async def send_command(self) -> None:

for bridge in self._motor_bridges.values():
if lost_communication_now:

# If we only just lost communications this iteration.
if not self._lost_communication:
rospy.loginfo(
Expand Down
3 changes: 0 additions & 3 deletions src/esw/cameras.py
Original file line number Diff line number Diff line change
Expand Up @@ -169,7 +169,6 @@ def __del__(self) -> None:


class StreamManager:

MAX_STREAMS: int = rospy.get_param("cameras/max_streams")
"""
The maximum number of streams that can be simultaneously sustained.
Expand Down Expand Up @@ -316,7 +315,6 @@ def handle_req(self, req: ChangeCamerasRequest) -> ChangeCamerasResponse:
# If a stream is being requested...
# (resolution == -1 means a request to cancel stream)
if req.camera_cmd.resolution >= 0:

# If we cannot handle any more streams, return False.
available_port_arr = [True, True, True, True]
for i, stream in enumerate(self._stream_by_device):
Expand Down Expand Up @@ -414,7 +412,6 @@ def send(

# Transmit loop
while True:

ret, frame = cap_send.read()
if not ret:
rospy.logerr("Empty frame")
Expand Down
1 change: 0 additions & 1 deletion src/esw/imu_driver.py
Original file line number Diff line number Diff line change
Expand Up @@ -91,7 +91,6 @@ def main():
attempts = 0

while not rospy.is_shutdown():

# try to read a line from the serial connection,
# if this fails 100 times in a row then end the program
try:
Expand Down
1 change: 0 additions & 1 deletion src/esw/science.py
Original file line number Diff line number Diff line change
Expand Up @@ -90,7 +90,6 @@ class ScienceBridge:
_last_mcu_active: Bool

def __init__(self) -> None:

self._active_publisher = rospy.Publisher("science_mcu_active", Bool, queue_size=1)

self._mcu_active_timeout_s = rospy.get_param("science/info/mcu_active_timeout_s")
Expand Down
1 change: 0 additions & 1 deletion src/navigation/gate.py
Original file line number Diff line number Diff line change
Expand Up @@ -216,7 +216,6 @@ class GateTraverseStateTransitions(Enum):


class GateTraverseState(BaseState):

STOP_THRESH = get_rosparam("gate/stop_thresh", 0.2)
DRIVE_FWD_THRESH = get_rosparam("gate/drive_fwd_thresh", 0.34) # 20 degrees
APPROACH_DISTANCE = get_rosparam("gate/approach_distance", 2.0)
Expand Down
1 change: 0 additions & 1 deletion src/navigation/partial_gate.py
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,6 @@ class PartialGateStateTransitions(Enum):


class PartialGateState(BaseState):

traj: Optional[PartialGateTrajectory] = None

def __init__(
Expand Down
10 changes: 5 additions & 5 deletions src/navigation/state.py
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
from abc import ABC
from typing import List
from typing import List, Optional

import smach
from context import Context
Expand All @@ -19,9 +19,9 @@ def __init__(
self,
context: Context,
own_transitions: List[str],
add_outcomes: List[str] = None,
add_input_keys: List[str] = None,
add_output_keys: List[str] = None,
add_outcomes: Optional[List[str]] = None,
add_input_keys: Optional[List[str]] = None,
add_output_keys: Optional[List[str]] = None,
):
add_outcomes = add_outcomes or []
add_input_keys = add_input_keys or []
Expand Down Expand Up @@ -72,7 +72,7 @@ def reset(self):

def evaluate(self, ud: smach.UserData) -> str:
"""Override me instead of execute!"""
pass
raise NotImplementedError


class DoneStateTransitions(Enum):
Expand Down
15 changes: 7 additions & 8 deletions src/navigation/waypoint.py
Original file line number Diff line number Diff line change
@@ -1,11 +1,10 @@
from typing import List

import numpy as np
import rospy
from typing import List, Optional

import tf2_ros
from context import Context, Environment

import numpy as np
from aenum import Enum, NoAlias
from context import Context
from state import BaseState
from util.ros_utils import get_rosparam

Expand All @@ -31,9 +30,9 @@ class WaypointState(BaseState):
def __init__(
self,
context: Context,
add_outcomes: List[str] = None,
add_input_keys: List[str] = None,
add_output_keys: List[str] = None,
add_outcomes: Optional[List[str]] = None,
add_input_keys: Optional[List[str]] = None,
add_output_keys: Optional[List[str]] = None,
):
add_outcomes = add_outcomes or []
add_input_keys = add_input_keys or []
Expand Down
4 changes: 0 additions & 4 deletions src/teleop/jetson/arm_trajectory_server.py
Original file line number Diff line number Diff line change
Expand Up @@ -74,17 +74,14 @@ def error_threshold_exceeded(feedback: FollowJointTrajectoryFeedback) -> str:


class MoveItAction(object):

# Rearranges the point path following the name convention joint_0, ... joint_6
def rearrange(self, joint_trajectory: JointTrajectory) -> None:

mapping = [joint_trajectory.joint_names.index(j) for j in conf_joint_names]

# Return early if already arranged properly
if mapping == sorted(mapping):
return
for point in joint_trajectory.points:

temp_positions: List[float] = []
temp_velocities: List[float] = []
temp_accelerations: List[float] = []
Expand Down Expand Up @@ -121,7 +118,6 @@ def __init__(self, name: str) -> None:

# Action callback
def execute_cb(self, goal: FollowJointTrajectoryGoal) -> None:

rospy.loginfo("Executing FollowJointTrajectory Action")
# It is required to rearrange the arrays because MoveIt doesn't guarantee order preservation
self.rearrange(goal.trajectory)
Expand Down
Loading

0 comments on commit 75749da

Please sign in to comment.