added Docker compose

This commit is contained in:
2026-02-10 17:58:06 -06:00
parent 3f68052144
commit 7da58dda3c
4 changed files with 47 additions and 9 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

36
docker-compose.yml Normal file
View File

@@ -0,0 +1,36 @@
services:
cpu:
image: moveit/moveit2:${DOCKER_IMAGE}
container_name: moveit2_container
privileged: true
network_mode: host
command: ["bash", "-c", "colcon build && 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: /bin/bash
deploy:
resources:
reservations:
devices:
- driver: nvidia
count: 1
capabilities: [gpu]
volumes:
- /tmp/.X11-unix:/tmp/.X11-unix
- $XAUTHORITY:/root/.Xauthority
environment:
QT_X11_NO_MITSHM: 1
DISPLAY: $DISPLAY
NVIDIA_VISIBLE_DEVICES: all
NVIDIA_DRIVER_CAPABILITIES: all

View File

@@ -43,16 +43,12 @@
#include <control_msgs/msg/joint_jog.hpp>
#include <std_srvs/srv/trigger.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/publisher.hpp>
#include <rclcpp/qos.hpp>
#include <rclcpp/qos_event.hpp>
#include <rclcpp/subscription.hpp>
#include <rclcpp/qos.hpp>
#include <rclcpp/time.hpp>
#include <rclcpp/utilities.hpp>
#include <thread>
// We'll just set up parameters here
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
*/
bool convertJoyToCmd(const std::vector<float>& axes, const std::vector<int>& buttons,
std::unique_ptr<geometry_msgs::msg::TwistStamped>& twist,
std::unique_ptr<control_msgs::msg::JointJog>& joint)
std::unique_ptr<geometry_msgs::msg::TwistStamped>& twist
// std::unique_ptr<control_msgs::msg::JointJog>& joint
)
{
// // Give joint jogging priority because it is only buttons
// // If any joint jog command is requested, we are only publishing joint commands
@@ -236,7 +233,7 @@ public:
updateCmdFrame(frame_to_publish_, msg->buttons);
// 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
twist_msg->header.frame_id = frame_to_publish_;