10 Commits

Author SHA1 Message Date
91fa23cd32 Fixed README 2026-02-10 18:54:40 -06:00
3e1b1683af Updated README 2026-02-10 18:50:53 -06:00
e3ad666fbc added --symlink-install 2026-02-10 18:42:53 -06:00
7da58dda3c added Docker compose 2026-02-10 17:58:06 -06:00
Riley M.
3f68052144 Merge pull request #30 from SHC-ASTRA/update-python
-> python 3.13
2026-02-09 21:49:08 -05:00
ryleu
c72f72dc32 -> python 3.13 2026-02-08 17:23:53 -06:00
Riley M.
61f5f1fc3e Merge pull request #29 from SHC-ASTRA/qos-disable
Qos disable
2026-02-07 18:20:04 -06:00
David Sharpe
65aab7f179 Fix nix cache (#27, fix-cache)
Fix cache
2026-02-04 02:34:16 -06:00
David
d9355f16e9 fix: EF gripper works again ._. 2026-01-31 18:32:39 -06:00
David
9fc120b09e fix: make QoS compatible with basestation-game 2026-01-31 17:21:52 -06:00
10 changed files with 79 additions and 27 deletions

4
.dockerignore Normal file
View File

@@ -0,0 +1,4 @@
.git
*.log
build/
install/

1
.env Normal file
View File

@@ -0,0 +1 @@
DOCKER_IMAGE=main-jazzy-tutorial-source

View File

@@ -11,6 +11,7 @@ You will use these packages to launch all rover-side ROS2 nodes.
- [Software Prerequisites](#software-prerequisites) - [Software Prerequisites](#software-prerequisites)
- [Nix](#nix) - [Nix](#nix)
- [ROS2 Humble + rosdep](#ros2-humble--rosdep) - [ROS2 Humble + rosdep](#ros2-humble--rosdep)
- [Docker](#docker)
- [Running](#running) - [Running](#running)
- [Testing Serial](#testing-serial) - [Testing Serial](#testing-serial)
- [Connecting the GuliKit Controller](#connecting-the-gulikit-controller) - [Connecting the GuliKit Controller](#connecting-the-gulikit-controller)
@@ -47,6 +48,17 @@ $ cd path/to/rover-ros2
$ rosdep install --from-paths src -y --ignore-src $ rosdep install --from-paths src -y --ignore-src
``` ```
### Docker
Using the docker compose file automatically builds the workspace and allows you to choose between running on the CPU or GPU for applications like Rviz2 and Gazebo:
```bash
# Run on CPU
$ docker compose run --rm --name rover-ros2-container cpu
# Run on GPU (NVidia only)
$ docker compose run --rm --name rover-ros2-container gpu
```
## Running ## Running
```bash ```bash

38
docker-compose.yml Normal file
View File

@@ -0,0 +1,38 @@
services:
cpu:
image: moveit/moveit2:${DOCKER_IMAGE}
container_name: moveit2_container
privileged: true
network_mode: host
command: ["bash", "-c", "colcon build --symlink-install && source /ros2_ws/install/setup.bash && exec bash"]
volumes:
- ./:/ros2_ws
- /tmp/.X11-unix:/tmp/.X11-unix
- $XAUTHORITY:/root/.Xauthority
working_dir: /ros2_ws
environment:
QT_X11_NO_MITSHM: 1
DISPLAY: $DISPLAY
gpu:
image: moveit/moveit2:${DOCKER_IMAGE}
container_name: moveit2_container
privileged: true
network_mode: host
command: ["bash", "-c", "colcon build --symlink-install && source /ros2_ws/install/setup.bash && exec bash"]
deploy:
resources:
reservations:
devices:
- driver: nvidia
count: 1
capabilities: [gpu]
volumes:
- ./:/ros2_ws
- /tmp/.X11-unix:/tmp/.X11-unix
- $XAUTHORITY:/root/.Xauthority
working_dir: /ros2_ws
environment:
QT_X11_NO_MITSHM: 1
DISPLAY: $DISPLAY
NVIDIA_VISIBLE_DEVICES: all
NVIDIA_DRIVER_CAPABILITIES: all

View File

@@ -25,7 +25,7 @@
name = "ASTRA Anchor"; name = "ASTRA Anchor";
packages = with pkgs; [ packages = with pkgs; [
colcon colcon
(python312.withPackages ( (python313.withPackages (
p: with p; [ p: with p; [
pyserial pyserial
pygame pygame

View File

@@ -49,7 +49,7 @@ class SerialRelay(Node):
# Create subscribers # Create subscribers
self.man_sub = self.create_subscription( self.man_sub = self.create_subscription(
ArmManual, "/arm/control/manual", self.send_manual, 10 ArmManual, "/arm/control/manual", self.send_manual, 2
) )
# New messages # New messages
@@ -190,7 +190,7 @@ class SerialRelay(Node):
command += f"can_relay_tovic,digit,39,{msg.effector_yaw},{msg.effector_roll}\n" command += f"can_relay_tovic,digit,39,{msg.effector_yaw},{msg.effector_roll}\n"
# command += f"can_relay_tovic,digit,26,{msg.gripper}\n" # no hardware rn command += f"can_relay_tovic,digit,26,{msg.gripper}\n" # no hardware rn
command += f"can_relay_tovic,digit,28,{msg.laser}\n" command += f"can_relay_tovic,digit,28,{msg.laser}\n"

View File

@@ -31,14 +31,14 @@ CORE_WHEEL_RADIUS = 0.171 # meters
CORE_GEAR_RATIO = 100.0 # Clucky: 100:1, Testbed: 64:1 CORE_GEAR_RATIO = 100.0 # Clucky: 100:1, Testbed: 64:1
control_qos = qos.QoSProfile( control_qos = qos.QoSProfile(
history=qos.QoSHistoryPolicy.KEEP_LAST, # history=qos.QoSHistoryPolicy.KEEP_LAST,
depth=2, depth=2,
reliability=qos.QoSReliabilityPolicy.BEST_EFFORT, # reliability=qos.QoSReliabilityPolicy.BEST_EFFORT,
durability=qos.QoSDurabilityPolicy.VOLATILE, # durability=qos.QoSDurabilityPolicy.VOLATILE,
deadline=Duration(seconds=1), # deadline=Duration(seconds=1),
lifespan=Duration(nanoseconds=500_000_000), # 500ms # lifespan=Duration(nanoseconds=500_000_000), # 500ms
liveliness=qos.QoSLivelinessPolicy.SYSTEM_DEFAULT, # liveliness=qos.QoSLivelinessPolicy.SYSTEM_DEFAULT,
liveliness_lease_duration=Duration(seconds=5), # liveliness_lease_duration=Duration(seconds=5),
) )
# Used to verify the length of an incoming VicCAN feedback message # Used to verify the length of an incoming VicCAN feedback message

View File

@@ -35,14 +35,14 @@ ARM_STOP_MSG = ArmManual() # "
BIO_STOP_MSG = BioControl() # " BIO_STOP_MSG = BioControl() # "
control_qos = qos.QoSProfile( control_qos = qos.QoSProfile(
history=qos.QoSHistoryPolicy.KEEP_LAST, # history=qos.QoSHistoryPolicy.KEEP_LAST,
depth=2, depth=2,
reliability=qos.QoSReliabilityPolicy.BEST_EFFORT, # reliability=qos.QoSReliabilityPolicy.BEST_EFFORT,
durability=qos.QoSDurabilityPolicy.VOLATILE, # durability=qos.QoSDurabilityPolicy.VOLATILE,
deadline=Duration(seconds=1), # deadline=Duration(seconds=1),
lifespan=Duration(nanoseconds=500_000_000), # 500ms # lifespan=Duration(nanoseconds=500_000_000), # 500ms
liveliness=qos.QoSLivelinessPolicy.SYSTEM_DEFAULT, # liveliness=qos.QoSLivelinessPolicy.SYSTEM_DEFAULT,
liveliness_lease_duration=Duration(seconds=5), # liveliness_lease_duration=Duration(seconds=5),
) )
CORE_MODE = "twist" # "twist" or "duty" CORE_MODE = "twist" # "twist" or "duty"

View File

@@ -43,16 +43,12 @@
#include <control_msgs/msg/joint_jog.hpp> #include <control_msgs/msg/joint_jog.hpp>
#include <std_srvs/srv/trigger.hpp> #include <std_srvs/srv/trigger.hpp>
#include <moveit_msgs/msg/planning_scene.hpp> #include <moveit_msgs/msg/planning_scene.hpp>
#include <rclcpp/client.hpp>
#include <rclcpp/experimental/buffers/intra_process_buffer.hpp>
#include <rclcpp/node.hpp> #include <rclcpp/node.hpp>
#include <rclcpp/publisher.hpp> #include <rclcpp/publisher.hpp>
#include <rclcpp/qos.hpp>
#include <rclcpp/qos_event.hpp>
#include <rclcpp/subscription.hpp> #include <rclcpp/subscription.hpp>
#include <rclcpp/qos.hpp>
#include <rclcpp/time.hpp> #include <rclcpp/time.hpp>
#include <rclcpp/utilities.hpp>
#include <thread>
// We'll just set up parameters here // We'll just set up parameters here
const std::string JOY_TOPIC = "/joy"; const std::string JOY_TOPIC = "/joy";
@@ -104,8 +100,9 @@ std::map<Button, double> BUTTON_DEFAULTS;
* @return return true if you want to publish a Twist, false if you want to publish a JointJog * @return return true if you want to publish a Twist, false if you want to publish a JointJog
*/ */
bool convertJoyToCmd(const std::vector<float>& axes, const std::vector<int>& buttons, bool convertJoyToCmd(const std::vector<float>& axes, const std::vector<int>& buttons,
std::unique_ptr<geometry_msgs::msg::TwistStamped>& twist, std::unique_ptr<geometry_msgs::msg::TwistStamped>& twist
std::unique_ptr<control_msgs::msg::JointJog>& joint) // std::unique_ptr<control_msgs::msg::JointJog>& joint
)
{ {
// // Give joint jogging priority because it is only buttons // // Give joint jogging priority because it is only buttons
// // If any joint jog command is requested, we are only publishing joint commands // // If any joint jog command is requested, we are only publishing joint commands
@@ -236,7 +233,7 @@ public:
updateCmdFrame(frame_to_publish_, msg->buttons); updateCmdFrame(frame_to_publish_, msg->buttons);
// Convert the joystick message to Twist or JointJog and publish // Convert the joystick message to Twist or JointJog and publish
if (convertJoyToCmd(msg->axes, msg->buttons, twist_msg, joint_msg)) if (convertJoyToCmd(msg->axes, msg->buttons, twist_msg))
{ {
// publish the TwistStamped // publish the TwistStamped
twist_msg->header.frame_id = frame_to_publish_; twist_msg->header.frame_id = frame_to_publish_;