diff --git a/src/navigation/approach_post.py b/src/navigation/approach_post.py index 424a93754..bd4c505b0 100644 --- a/src/navigation/approach_post.py +++ b/src/navigation/approach_post.py @@ -1,9 +1,9 @@ import tf2_ros -import rospy -from context import Context from aenum import Enum, NoAlias from geometry_msgs.msg import Twist from util.ros_utils import get_rosparam + +from context import Context from state import BaseState diff --git a/src/navigation/context.py b/src/navigation/context.py index 23cdac886..aa55d29a0 100644 --- a/src/navigation/context.py +++ b/src/navigation/context.py @@ -1,25 +1,23 @@ from __future__ import annotations -from pdb import post_mortem -import rospy -import tf2_ros -from geometry_msgs.msg import Twist + +from dataclasses import dataclass +from typing import ClassVar, Optional, List, Tuple + import mrover.msg import mrover.srv -from util.SE3 import SE3 -from visualization_msgs.msg import Marker -from typing import ClassVar, Optional, List, Tuple import numpy as np -from dataclasses import dataclass -from shapely.geometry import Point, LineString -from mrover.msg import Waypoint, GPSWaypoint, EnableAuton, WaypointType, GPSPointList import pymap3d -from drive import DriveController -from util.ros_utils import get_rosparam - +import rospy +import tf2_ros +from geometry_msgs.msg import Twist +from mrover.msg import Waypoint, GPSWaypoint, EnableAuton, WaypointType, GPSPointList +from shapely.geometry import Point from std_msgs.msg import Time, Bool -from drive import DriveController +from util.SE3 import SE3 from util.ros_utils import get_rosparam +from visualization_msgs.msg import Marker +from drive import DriveController TAG_EXPIRATION_TIME_SECONDS = 60 diff --git a/src/navigation/drive.py b/src/navigation/drive.py index 31057f2a0..1264c345c 100644 --- a/src/navigation/drive.py +++ b/src/navigation/drive.py @@ -1,9 +1,9 @@ from __future__ import annotations -from typing import Tuple, Optional -import numpy as np -import rospy + from enum import Enum +from typing import Tuple, Optional +import numpy as np from geometry_msgs.msg import Twist from util.SE3 import SE3 from util.np_utils import angle_to_rotate, normalized diff --git a/src/navigation/failure_identification/failure_identification.py b/src/navigation/failure_identification/failure_identification.py index 23cf994f4..3e9123825 100755 --- a/src/navigation/failure_identification/failure_identification.py +++ b/src/navigation/failure_identification/failure_identification.py @@ -1,20 +1,21 @@ #!/usr/bin/env python3 -import rospy + +from pathlib import Path +from typing import Optional + import message_filters -from mrover.msg import MotorsStatus +import numpy as np +import pandas as pd +import rospy from geometry_msgs.msg import Twist +from mrover.msg import MotorsStatus from nav_msgs.msg import Odometry +from pandas import DataFrame from smach_msgs.msg import SmachContainerStatus from std_msgs.msg import Bool -import pandas as pd -from pandas import DataFrame -from watchdog import WatchDog -import numpy as np -import os -from pathlib import Path from util.ros_utils import get_rosparam -from util.SO3 import SO3 -from typing import Optional + +from watchdog import WatchDog DATAFRAME_MAX_SIZE = get_rosparam("failure_identification/dataframe_max_size", 200) POST_RECOVERY_GRACE_PERIOD = get_rosparam("failure_identification/post_recovery_grace_period", 5.0) diff --git a/src/navigation/failure_identification/watchdog.py b/src/navigation/failure_identification/watchdog.py index 5ad0cbd9b..8a63fe9e6 100644 --- a/src/navigation/failure_identification/watchdog.py +++ b/src/navigation/failure_identification/watchdog.py @@ -1,9 +1,9 @@ +from typing import Tuple + import numpy as np -import rospy from pandas import DataFrame -from util.ros_utils import get_rosparam from util.SO3 import SO3 -from typing import Tuple +from util.ros_utils import get_rosparam WINDOW_SIZE = get_rosparam("watchdog/window_size", 100) ANGULAR_THRESHOLD = get_rosparam("watchdog/angular_threshold", 0.001) diff --git a/src/navigation/gate.py b/src/navigation/gate.py index 3638e8004..280a386cd 100644 --- a/src/navigation/gate.py +++ b/src/navigation/gate.py @@ -1,21 +1,18 @@ from __future__ import annotations -from typing import ClassVar, Optional -from unicodedata import normalize -from context import Gate, Context -import numpy as np -import rospy +from dataclasses import dataclass +from typing import Optional -from context import Context, Environment, Rover, convert_cartesian_to_gps +import numpy as np from aenum import Enum, NoAlias -from state import BaseState -from trajectory import Trajectory -from dataclasses import dataclass -from drive import DriveController +from mrover.msg import GPSPointList +from shapely.geometry import LineString, Polygon, Point from util.np_utils import normalized, perpendicular_2d from util.ros_utils import get_rosparam -from shapely.geometry import LineString, Polygon, Point -from mrover.msg import GPSPointList + +from context import Context, Rover, convert_cartesian_to_gps +from context import Gate +from state import BaseState STOP_THRESH = get_rosparam("gate/stop_thresh", 0.2) DRIVE_FWD_THRESH = get_rosparam("gate/drive_fwd_thresh", 0.34) # 20 degrees diff --git a/src/navigation/navigation.py b/src/navigation/navigation.py index aba60a399..4a3c82279 100755 --- a/src/navigation/navigation.py +++ b/src/navigation/navigation.py @@ -7,18 +7,19 @@ import rospy import smach import smach_ros +from navigation.state import DoneState, DoneStateTransitions, OffState, OffStateTransitions +from smach.log import loginfo +from smach.log import set_loggers +from std_msgs.msg import String + +from approach_post import ApproachPostState, ApproachPostStateTransitions from context import Context from gate import GateTraverseState, GateTraverseStateTransitions -from approach_post import ApproachPostState, ApproachPostStateTransitions -from navigation.state import DoneState, DoneStateTransitions, OffState, OffStateTransitions -from waypoint import WaypointState, WaypointStateTransitions -from search import SearchState, SearchStateTransitions -from recovery import RecoveryState, RecoveryStateTransitions from partial_gate import PartialGateState, PartialGateStateTransitions from post_backup import PostBackupState, PostBackupTransitions -from smach.log import set_loggers -from smach.log import loginfo, logwarn, logerr -from std_msgs.msg import String +from recovery import RecoveryState, RecoveryStateTransitions +from search import SearchState, SearchStateTransitions +from waypoint import WaypointState, WaypointStateTransitions class Navigation(threading.Thread): diff --git a/src/navigation/partial_gate.py b/src/navigation/partial_gate.py index 88e1df022..722484a10 100644 --- a/src/navigation/partial_gate.py +++ b/src/navigation/partial_gate.py @@ -1,12 +1,13 @@ from dataclasses import dataclass -import numpy as np +from typing import Optional +import numpy as np +from aenum import Enum, NoAlias from util import np_utils -from typing import Optional + +from context import Context from state import BaseState from trajectory import Trajectory -from aenum import Enum, NoAlias -from context import Context STOP_THRESH = 0.2 DRIVE_FWD_THRESH = 0.95 diff --git a/src/navigation/post_backup.py b/src/navigation/post_backup.py index f56edd01e..66f278b27 100644 --- a/src/navigation/post_backup.py +++ b/src/navigation/post_backup.py @@ -1,17 +1,20 @@ from __future__ import annotations + from dataclasses import dataclass -import numpy as np from typing import Optional -from state import BaseState -from trajectory import Trajectory + +import numpy as np +import rospy +import tf2_ros from aenum import Enum, NoAlias -from context import Context -from util.ros_utils import get_rosparam -from util.np_utils import perpendicular_2d from shapely.geometry import Point, LineString from util.SE3 import SE3 -import tf2_ros -import rospy +from util.np_utils import perpendicular_2d +from util.ros_utils import get_rosparam + +from context import Context +from state import BaseState +from trajectory import Trajectory POST_RADIUS = get_rosparam("gate/post_radius", 0.7) * get_rosparam("single_fiducial/post_avoidance_multiplier", 1.42) BACKUP_DISTANCE = get_rosparam("recovery/recovery_distance", 2.0) diff --git a/src/navigation/recovery.py b/src/navigation/recovery.py index 3d4be3b8a..7f0e38d68 100644 --- a/src/navigation/recovery.py +++ b/src/navigation/recovery.py @@ -1,15 +1,14 @@ -import smach -from typing import List from context import Context -from aenum import Enum, NoAlias -from state import BaseState -from geometry_msgs.msg import Twist -import rospy -import numpy as np from typing import Optional -from util.np_utils import perpendicular_2d, rotate_2d + +import numpy as np +import rospy +from aenum import Enum, NoAlias +from util.np_utils import rotate_2d from util.ros_utils import get_rosparam +from context import Context +from state import BaseState STOP_THRESH = get_rosparam("recovery/stop_thresh", 0.2) DRIVE_FWD_THRESH = get_rosparam("recovery/drive_fwd_thresh", 0.34) # 20 degrees diff --git a/src/navigation/search.py b/src/navigation/search.py index e6873223a..964380688 100644 --- a/src/navigation/search.py +++ b/src/navigation/search.py @@ -1,15 +1,16 @@ from __future__ import annotations + +from dataclasses import dataclass from typing import Optional import numpy as np +from aenum import Enum, NoAlias +from mrover.msg import GPSPointList +from util.ros_utils import get_rosparam from context import Context, convert_cartesian_to_gps -from aenum import Enum, NoAlias from state import BaseState -from dataclasses import dataclass from trajectory import Trajectory -from mrover.msg import GPSPointList -from util.ros_utils import get_rosparam @dataclass diff --git a/src/navigation/state.py b/src/navigation/state.py index c35295f33..9084ab741 100644 --- a/src/navigation/state.py +++ b/src/navigation/state.py @@ -1,11 +1,12 @@ -from abc import ABC +from abc import ABC, abstractmethod from typing import List, Optional import smach -from context import Context from aenum import Enum, NoAlias from geometry_msgs.msg import Twist +from context import Context + class BaseState(smach.State, ABC): """ @@ -70,9 +71,10 @@ def reset(self): """ pass + @abstractmethod def evaluate(self, ud: smach.UserData) -> str: """Override me instead of execute!""" - raise NotImplementedError + ... class DoneStateTransitions(Enum): diff --git a/src/navigation/trajectory.py b/src/navigation/trajectory.py index 674a0f582..a44dceb3a 100644 --- a/src/navigation/trajectory.py +++ b/src/navigation/trajectory.py @@ -1,4 +1,5 @@ from dataclasses import dataclass, field + import numpy as np diff --git a/src/navigation/waypoint.py b/src/navigation/waypoint.py index 98e6a5aac..9300660a7 100644 --- a/src/navigation/waypoint.py +++ b/src/navigation/waypoint.py @@ -1,12 +1,12 @@ from typing import List, Optional -import tf2_ros - import numpy as np +import tf2_ros from aenum import Enum, NoAlias +from util.ros_utils import get_rosparam + from context import Context from state import BaseState -from util.ros_utils import get_rosparam class WaypointStateTransitions(Enum): diff --git a/starter_project/autonomy/config/starter_project.rviz b/starter_project/autonomy/config/starter_project.rviz index 3f5631db0..31d1b36ae 100644 --- a/starter_project/autonomy/config/starter_project.rviz +++ b/starter_project/autonomy/config/starter_project.rviz @@ -173,7 +173,7 @@ Visualization Manager: Value: false - Class: rviz/Image Enabled: true - Image Topic: /camera/color/image_raw + Image Topic: /camera/right/image Max Value: 1 Median window: 5 Min Value: 0 diff --git a/starter_project/autonomy/format.sh b/starter_project/autonomy/format.sh new file mode 100755 index 000000000..bc7e569ae --- /dev/null +++ b/starter_project/autonomy/format.sh @@ -0,0 +1,44 @@ +#!/usr/bin/env bash + +# See: https://vaneyckt.io/posts/safer_bash_scripts_with_set_euxo_pipefail/ +set -Eeuo pipefail + +readonly RED='\033[0;31m' +readonly NC='\033[0m' + +BLACK_ARGS=( + "--line-length=120" + "--color" +) + +# Just do a dry run if the "fix" argument is not passed +if [ $# -eq 0 ] || [ "$1" != "--fix" ]; then + BLACK_ARGS+=("--diff") # Show difference + BLACK_ARGS+=("--check") # Exit with non-zero code if changes are required (for CI) +fi + +function print_update_error() { + echo -e "${RED}[Error] Please update with ./ansible.sh build.yml${NC}" + exit 1 +} + +function find_executable() { + local readonly executable="$1" + local readonly version="$2" + local readonly path=$(which "${executable}") + if [ ! -x "${path}" ]; then + echo -e "${RED}[Error] Could not find ${executable}${NC}" + print_update_error + fi + if ! "${path}" --version | grep -q "${version}"; then + echo -e "${RED}[Error] Wrong ${executable} version${NC}" + print_update_error + fi + echo "${path}" +} + +readonly BLACK_PATH=$(find_executable black 23.9.1) + +echo +echo "Style checking Python with black ..." +"${BLACK_PATH}" "${BLACK_ARGS[@]}" ./src diff --git a/starter_project/autonomy/lint.sh b/starter_project/autonomy/lint.sh new file mode 100755 index 000000000..1b45973b5 --- /dev/null +++ b/starter_project/autonomy/lint.sh @@ -0,0 +1,33 @@ +#!/usr/bin/env bash + +# See: https://vaneyckt.io/posts/safer_bash_scripts_with_set_euxo_pipefail/ +set -Eeuo pipefail + +readonly RED='\033[0;31m' +readonly NC='\033[0m' + +function print_update_error() { + echo -e "${RED}[Error] Please update with ./ansible.sh build.yml${NC}" + exit 1 +} + +function find_executable() { + local readonly executable="$1" + local readonly version="$2" + local readonly path=$(which "${executable}") + if [ ! -x "${path}" ]; then + echo -e "${RED}[Error] Could not find ${executable}${NC}" + print_update_error + fi + if ! "${path}" --version | grep -q "${version}"; then + echo -e "${RED}[Error] Wrong ${executable} version${NC}" + print_update_error + fi + echo "${path}" +} + +readonly MYPY_PATH=$(find_executable mypy 1.5.1) + +echo +echo "Style checking Python with mypy ..." +"${MYPY_PATH}" --config-file=mypy.ini --check ./src diff --git a/starter_project/autonomy/mypy.ini b/starter_project/autonomy/mypy.ini new file mode 120000 index 000000000..141a30f41 --- /dev/null +++ b/starter_project/autonomy/mypy.ini @@ -0,0 +1 @@ +../../mypy.ini \ No newline at end of file diff --git a/starter_project/autonomy/src/localization.py b/starter_project/autonomy/src/localization.py index 4fe23dabf..b8ff5423a 100755 --- a/starter_project/autonomy/src/localization.py +++ b/starter_project/autonomy/src/localization.py @@ -31,13 +31,11 @@ def gps_callback(self, msg: NavSatFix): """ This function will be called every time this node receives a NavSatFix message on the /gps topic. It should read the GPS location from the given NavSatFix message, - convert it to cartesian coordiantes, store that value in `self.pose`, then publish + convert it to cartesian coordinates, store that value in `self.pose`, then publish that pose to the TF tree. """ # TODO - - def imu_callback(self, msg: Imu): """ This function will be called every time this node receives an Imu message @@ -46,7 +44,6 @@ def imu_callback(self, msg: Imu): """ # TODO - @staticmethod def spherical_to_cartesian(spherical_coord: np.ndarray, reference_coord: np.ndarray) -> np.ndarray: """ @@ -54,9 +51,9 @@ def spherical_to_cartesian(spherical_coord: np.ndarray, reference_coord: np.ndar coordinates into cartesian (x, y, z) coordinates using the specified reference point as the center of the tangent plane used for approximation. :param spherical_coord: the spherical coordinate to convert, - given as a numpy array [latiude, longitude] + given as a numpy array [latitude, longitude] :param reference_coord: the reference coordinate to use for conversion, - given as a numpy array [latiude, longitude] + given as a numpy array [latitude, longitude] :returns: the approximated cartesian coordinates in meters, given as a numpy array [x, y, z] """ # TODO @@ -74,4 +71,4 @@ def main(): if __name__ == "__main__": - main() \ No newline at end of file + main() diff --git a/starter_project/autonomy/src/navigation/context.py b/starter_project/autonomy/src/navigation/context.py index 75e476e36..4bbd06f61 100644 --- a/starter_project/autonomy/src/navigation/context.py +++ b/starter_project/autonomy/src/navigation/context.py @@ -1,15 +1,15 @@ from __future__ import annotations -from re import S + +from dataclasses import dataclass +from typing import Optional + +import numpy as np import rospy import tf2_ros from geometry_msgs.msg import Twist from mrover.msg import StarterProjectTag -import mrover.srv from util.SE3 import SE3 from visualization_msgs.msg import Marker -from typing import ClassVar, Optional -import numpy as np -from dataclasses import dataclass @dataclass @@ -17,17 +17,18 @@ class Rover: ctx: Context def get_pose(self) -> Optional[SE3]: - #TODO: return the pose of the rover (or None if we don't have one (catch exception)) + # TODO: return the pose of the rover (or None if we don't have one (catch exception)) pass def send_drive_command(self, twist: Twist): - #TODO: send the Twist message to the rover + # TODO: send the Twist message to the rover pass def send_drive_stop(self): - #TODO: tell the rover to stop + # TODO: tell the rover to stop pass + @dataclass class Environment: """ @@ -38,18 +39,19 @@ class Environment: ctx: Context fid_pos: Optional[StarterProjectTag] - def recieve_fid_data(self, message : StarterProjectTag): - #TODO: handle incoming FID data messages here + def receive_fid_data(self, message: StarterProjectTag): + # TODO: handle incoming FID data messages here pass def get_fid_data(self) -> Optional[StarterProjectTag]: """ - Retrieves the last recieved message regarding fid pose + Retrieves the last received message regarding fid pose if it exists, otherwise returns None """ - #TODO: return either None or your position message + # TODO: return either None or your position message pass + class Context: tf_buffer: tf2_ros.Buffer tf_listener: tf2_ros.TransformListener @@ -68,4 +70,4 @@ def __init__(self): self.vis_publisher = rospy.Publisher("nav_vis", Marker) self.rover = Rover(self) self.env = Environment(self, None) - self.fid_listener = rospy.Subscriber("/tag", StarterProjectTag,self.env.recieve_fid_data) \ No newline at end of file + self.fid_listener = rospy.Subscriber("/tag", StarterProjectTag, self.env.receive_fid_data) diff --git a/starter_project/autonomy/src/navigation/drive.py b/starter_project/autonomy/src/navigation/drive.py index 882388940..0bf724678 100644 --- a/starter_project/autonomy/src/navigation/drive.py +++ b/starter_project/autonomy/src/navigation/drive.py @@ -1,7 +1,6 @@ from typing import Tuple import numpy as np - from geometry_msgs.msg import Twist from util.SE3 import SE3 @@ -54,4 +53,4 @@ def get_drive_command( # 1 is target alignment (dot product of two normalized vectors that are parallel is 1) error = 1.0 - alignment cmd_vel.angular.z = np.clip(error * TURNING_P * sign, MIN_DRIVING_EFFORT, MAX_DRIVING_EFFORT) - return cmd_vel, False \ No newline at end of file + return cmd_vel, False diff --git a/starter_project/autonomy/src/navigation/drive_state.py b/starter_project/autonomy/src/navigation/drive_state.py index dd315e383..bae1d07f1 100644 --- a/starter_project/autonomy/src/navigation/drive_state.py +++ b/starter_project/autonomy/src/navigation/drive_state.py @@ -1,31 +1,30 @@ -from multiprocessing import context -from state import BaseState import numpy as np + from context import Context from drive import get_drive_command +from state import BaseState + class DriveState(BaseState): def __init__(self, context: Context): super().__init__( context, - #TODO: + # TODO: add_outcomes=["TODO: add outcomes here"], ) def evaluate(self, ud): target = np.array([5.5, 2.0, 0.0]) - - #TODO: get the rover's pose, if it doesn't exist stay in DriveState (with outcome "driving_to_point") - - #TODO: get the drive command and completion status based on target and pose + + # TODO: get the rover's pose, if it doesn't exist stay in DriveState (with outcome "driving_to_point") + + # TODO: get the drive command and completion status based on target and pose # (HINT: use get_drive_command(), with completion_thresh set to 0.7 and turn_in_place_thresh set to 0.2) - - #TODO: if we are finished getting to the target, go to TagSeekState (with outcome "reached_point") - - #TODO: send the drive command to the rover - - #TODO: tell smach to stay in the DriveState by returning with outcome "driving_to_point" - - pass - + # TODO: if we are finished getting to the target, go to TagSeekState (with outcome "reached_point") + + # TODO: send the drive command to the rover + + # TODO: tell smach to stay in the DriveState by returning with outcome "driving_to_point" + + pass diff --git a/starter_project/autonomy/src/navigation/navigation_starter_project.py b/starter_project/autonomy/src/navigation/navigation_starter_project.py index ef1a96c86..a3f00f0dd 100755 --- a/starter_project/autonomy/src/navigation/navigation_starter_project.py +++ b/starter_project/autonomy/src/navigation/navigation_starter_project.py @@ -11,8 +11,8 @@ # navigation specific imports from context import Context -from state import DoneState from drive_state import DriveState +from state import DoneState from tag_seek import TagSeekState @@ -29,16 +29,16 @@ def __init__(self, context: Context): self.sis = smach_ros.IntrospectionServer("", self.state_machine, "/SM_ROOT") self.sis.start() with self.state_machine: - #TODO: add DriveState and its transitions here - + # TODO: add DriveState and its transitions here + # DoneState and its transitions self.state_machine.add( "DoneState", DoneState(self.context), transitions={"done": "DoneState"}, ) - #TODO: add TagSeekState and its transitions here - + # TODO: add TagSeekState and its transitions here + def run(self): self.state_machine.execute() @@ -53,7 +53,7 @@ def stop(self): def main(): # TODO: init a node called "navigation" - + # context and navigation objects context = Context() navigation = Navigation(context) diff --git a/starter_project/autonomy/src/navigation/state.py b/starter_project/autonomy/src/navigation/state.py index 5a40b4f0e..c1a8e623c 100644 --- a/starter_project/autonomy/src/navigation/state.py +++ b/starter_project/autonomy/src/navigation/state.py @@ -1,10 +1,11 @@ -from abc import ABC -from typing import List +from abc import ABC, abstractmethod +from typing import List, Optional import smach -from context import Context from geometry_msgs.msg import Twist +from context import Context + class BaseState(smach.State, ABC): """ @@ -16,9 +17,9 @@ class BaseState(smach.State, ABC): 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 [] @@ -42,9 +43,10 @@ def execute(self, ud): return "terminated" return self.evaluate(ud) + @abstractmethod def evaluate(self, ud: smach.UserData) -> str: """Override me instead of execute!""" - pass + ... class DoneState(BaseState): diff --git a/starter_project/autonomy/src/navigation/tag_seek.py b/starter_project/autonomy/src/navigation/tag_seek.py index c1f597657..577731516 100644 --- a/starter_project/autonomy/src/navigation/tag_seek.py +++ b/starter_project/autonomy/src/navigation/tag_seek.py @@ -1,28 +1,30 @@ -from state import BaseState -from context import Context from geometry_msgs.msg import Twist +from context import Context +from state import BaseState + + class TagSeekState(BaseState): def __init__(self, context: Context): super().__init__( context, - #TODO: add outcomes + # TODO: add outcomes add_outcomes=["TODO: add outcomes here"], ) def evaluate(self, ud): DISTANCE_TOLERANCE = 0.99 ANUGLAR_TOLERANCE = 0.3 - #TODO: get the tag's location and properties (HINT: use get_fid_data() from context.env) + # TODO: get the tag's location and properties (HINT: use get_fid_data() from context.env) - #TODO: if we don't have a tag: go to the DoneState (with outcome "failure") + # TODO: if we don't have a tag: go to the DoneState (with outcome "failure") - #TODO: if we are within angular and distance tolerances: go to DoneState (with outcome "success") + # TODO: if we are within angular and distance tolerances: go to DoneState (with outcome "success") - #TODO: figure out the Twist command to be applied to move the rover closer to the tag + # TODO: figure out the Twist command to be applied to move the rover closer to the tag - #TODO: send Twist command to rover + # TODO: send Twist command to rover - #TODO: stay in the TagSeekState (with outcome "working") + # TODO: stay in the TagSeekState (with outcome "working") - pass \ No newline at end of file + pass diff --git a/starter_project/autonomy/src/util/SE3.py b/starter_project/autonomy/src/util/SE3.py index 70474b496..824a16bb0 100644 --- a/starter_project/autonomy/src/util/SE3.py +++ b/starter_project/autonomy/src/util/SE3.py @@ -1,13 +1,14 @@ from __future__ import annotations + from dataclasses import dataclass, field import numpy as np -import tf2_ros import rospy - -from .np_utils import numpify +import tf2_ros from geometry_msgs.msg import TransformStamped, Vector3, Quaternion + from .SO3 import SO3 +from .np_utils import numpify @dataclass(frozen=True) @@ -92,7 +93,7 @@ def pos_distance_to(self, p: SE3) -> float: :param p: another SE3 :returns: euclidean distance between the two SE3s """ - return np.linalg.norm(p.position - self.position) + return np.linalg.norm(p.position - self.position) # type: ignore def is_approx(self, p: SE3, tolerance=1e-8) -> bool: """ diff --git a/starter_project/autonomy/src/util/SO3.py b/starter_project/autonomy/src/util/SO3.py index 984d207a3..7eca45ade 100644 --- a/starter_project/autonomy/src/util/SO3.py +++ b/starter_project/autonomy/src/util/SO3.py @@ -1,5 +1,7 @@ from __future__ import annotations + from dataclasses import dataclass, field + import numpy as np from tf.transformations import ( quaternion_inverse, diff --git a/starter_project/autonomy/src/util/np_utils.py b/starter_project/autonomy/src/util/np_utils.py index 923b7304c..a1f361163 100644 --- a/starter_project/autonomy/src/util/np_utils.py +++ b/starter_project/autonomy/src/util/np_utils.py @@ -1,7 +1,8 @@ -import numpy as np +from typing import Union +import numpy as np from geometry_msgs.msg import Vector3, Quaternion, Point -from typing import Union + def _translation_to_numpy(translation: Vector3) -> np.ndarray: return np.array([translation.x, translation.y, translation.z]) @@ -19,6 +20,7 @@ def normalized(v): norm = np.linalg.norm(v) return v / norm + def numpify(msg: Union[Vector3, Quaternion, Point]) -> np.ndarray: if msg.__class__ == Vector3: return _translation_to_numpy(msg) @@ -27,4 +29,4 @@ def numpify(msg: Union[Vector3, Quaternion, Point]) -> np.ndarray: elif msg.__class__ == Point: return _point_to_numpy(msg) else: - raise Exception("type of msg must be either Vector3 or Quaternion!!!") \ No newline at end of file + raise Exception("type of msg must be either Vector3 or Quaternion!!!") diff --git a/style.sh b/style.sh index 39ff40b7c..779ef6d8e 100755 --- a/style.sh +++ b/style.sh @@ -6,46 +6,46 @@ set -Eeuo pipefail readonly RED='\033[0;31m' readonly NC='\033[0m' -print_update_error() { - echo -e "${RED}[Error] Please update with ./ansible.sh build.yml${NC}" - exit 1 -} - -## Check that all tools are installed - -readonly clang_format_executable=clang-format-16 -readonly clang_format_executable_path=$(which "$clang_format_executable") -if [ ! -x "$clang_format_executable_path" ]; then - echo -e "${RED}[Error] Could not find clang-format-16${NC}" - print_update_error -fi - +BLACK_ARGS=( + "--line-length=120" + "--color" +) +CLANG_FORMAT_ARGS=( + "-style=file" +) -readonly black_executable=black -readonly black_executable_path=$(which "$black_executable") -if [ ! -x "$black_executable_path" ]; then - echo -e "${RED}[Error] Could not find black${NC}" - print_update_error +# Just do a dry run if the "fix" argument is not passed +if [ $# -eq 0 ] || [ "$1" != "--fix" ]; then + BLACK_ARGS+=("--diff") # Show difference + BLACK_ARGS+=("--check") # Exit with non-zero code if changes are required (for CI) + CLANG_FORMAT_ARGS+=("--dry-run") fi -# Style check Python with black -if ! black --version | grep -q 'black, 23.9.1'; then - echo -e "${RED}[Error] Wrong black version${NC}" - print_update_error -fi +function print_update_error() { + echo -e "${RED}[Error] Please update with ./ansible.sh build.yml${NC}" + exit 1 +} +function find_executable() { + local readonly executable="$1" + local readonly version="$2" + local readonly path=$(which "${executable}") + if [ ! -x "${path}" ]; then + echo -e "${RED}[Error] Could not find ${executable}${NC}" + print_update_error + fi + if ! "${path}" --version | grep -q "${version}"; then + echo -e "${RED}[Error] Wrong ${executable} version${NC}" + print_update_error + fi + echo "${path}" +} -readonly mypy_executable=mypy -readonly mypy_executable_path=$(which "$mypy_executable") -if [ ! -x "$mypy_executable_path" ]; then - echo -e "${RED}[Error] Could not find mypy${NC}" - print_update_error -fi +## Check that all tools are installed -if ! mypy --version | grep -q 'mypy 1.5.1'; then - echo -e "${RED}[Error] Wrong mypy version${NC}" - print_update_error -fi +readonly CLANG_FORMAT_PATH=$(find_executable clang-format-16 16.0) +readonly BLACK_PATH=$(find_executable black 23.9.1) +readonly MYPY_PATH=$(find_executable mypy 1.5.1) ## Run checks @@ -56,14 +56,14 @@ readonly FOLDERS=( ./src/util ) for FOLDER in "${FOLDERS[@]}"; do - find "${FOLDER}" -regex '.*\.\(cpp\|hpp\|h\)' -exec "$clang_format_executable_path" --dry-run -style=file -i {} \; + find "${FOLDER}" -regex '.*\.\(cpp\|hpp\|h\)' -exec "${CLANG_FORMAT_PATH}" "${CLANG_FORMAT_ARGS[@]}" -i {} \; done echo "Done" echo echo "Style checking Python with black ..." -"$black_executable_path" --line-length=120 ./src ./scripts +"$BLACK_PATH" "${BLACK_ARGS[@]}" ./src ./scripts echo echo "Style checking Python with mypy ..." -"$mypy_executable_path" --config-file mypy.ini --check ./src ./scripts +"$MYPY_PATH" --config-file=mypy.ini --check ./src ./scripts