Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion mypy.ini
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
[mypy]
strict = True
exclude = tests/data/pypi-indexes
exclude = tests/data/pypi-indexes|tests/data/pixi_build/ros-workspace
files = tests,scripts
60 changes: 58 additions & 2 deletions scripts/build-repos.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@
"""

import os
import shutil
import subprocess
import sys
from pathlib import Path
Expand All @@ -36,13 +37,21 @@ class PixiBuildError(Exception):


def run_command(
cmd: list[str], cwd: Path | None = None, capture_output: bool = True
cmd: list[str],
cwd: Path | None = None,
capture_output: bool = True,
env: dict[str, str] | None = None,
) -> tuple[int, str, str]:
"""Run a command and return exit code, stdout, and stderr."""
result = subprocess.run(cmd, cwd=cwd, capture_output=capture_output, text=True)
result = subprocess.run(cmd, cwd=cwd, capture_output=capture_output, text=True, env=env)
return result.returncode, result.stdout, result.stderr


def executable_name(base: str) -> str:
"""Return the platform specific executable name."""
return f"{base}.exe" if sys.platform.startswith("win") else base


def is_git_worktree(path: Path) -> bool:
"""Check if the given path is inside a git work tree (repo or worktree)."""
if not path.exists() or not path.is_dir():
Expand Down Expand Up @@ -89,6 +98,52 @@ def build_executables(repo_path: Path) -> None:
raise PixiBuildError(error_msg)


def build_ros_backend(repo_path: Path) -> None:
"""Build the pixi-build-ros backend located in backends/pixi-build-ros."""
ros_backend_dir = repo_path / "backends" / "pixi-build-ros"
if not ros_backend_dir.is_dir():
print("⚠️ pixi-build-ros backend directory not found, skipping")
return

print(f"🔨 Building pixi-build-ros backend in {ros_backend_dir}")
returncode, stdout, stderr = run_command(
[
"pixi",
"install",
"--manifest-path",
str(ros_backend_dir.joinpath("pixi.toml")),
],
cwd=ros_backend_dir,
)

if returncode != 0:
error_msg = "Failed to build pixi-build-ros backend"
if stderr:
error_msg += f": {stderr}"
if stdout:
error_msg += f" (Output: {stdout})"
raise PixiBuildError(error_msg)

ros_executable = executable_name("pixi-build-ros")
source_binary = ros_backend_dir.joinpath(".pixi", "envs", "default", "bin", ros_executable)

if not source_binary.exists():
raise PixiBuildError(
f"pixi-build-ros binary not found at '{source_binary}'."
" Ensure pixi install completed successfully."
)

target_dir = repo_path / "target" / "pixi" / "release"
target_dir.mkdir(parents=True, exist_ok=True)
target_binary = target_dir / ros_executable

if target_binary.exists():
target_binary.unlink()

shutil.copy2(source_binary, target_binary)
print("✅ Successfully built pixi-build-ros backend")


def process_repository(repo_path: Path, repo_name: str) -> None:
"""Process a single repository: verify, pull if on main, and build."""
print(f"\n{'=' * 60}")
Expand Down Expand Up @@ -156,6 +211,7 @@ def main() -> None:

try:
process_repository(build_backends_repo_path, "BUILD_BACKENDS_REPO")
build_ros_backend(build_backends_repo_path)
except Exception as e:
print(f"❌ Error processing BUILD_BACKENDS_REPO: {e}")
success = False
Expand Down
41,203 changes: 41,203 additions & 0 deletions tests/data/pixi_build/ros-workspace/pixi.lock

Large diffs are not rendered by default.

20 changes: 20 additions & 0 deletions tests/data/pixi_build/ros-workspace/pixi.toml
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
[workspace]
channels = [
"https://prefix.dev/pixi-build-backends",
"https://prefix.dev/conda-forge",
"https://prefix.dev/robostack-staging",
]
platforms = ["osx-arm64", "linux-64", "win-64", "linux-aarch64"]
preview = ["pixi-build"]

[tasks]
navigator = "ros2 run navigator navigator"
navigator_py = "ros2 run navigator_py navigator"
sim = "ros2 run turtlesim turtlesim_node"
talker = "ros2 run talker_py talker"

[dependencies]
ros-humble-desktop = ">=0.10.0,<0.11"
ros-humble-navigator = { path = "src/navigator" }
ros-humble-navigator-py = { path = "src/navigator_py" }
ros-humble-talker-py = { path = "src/talker-py" }
41 changes: 41 additions & 0 deletions tests/data/pixi_build/ros-workspace/src/navigator/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
cmake_minimum_required(VERSION 3.8)
project(navigator)

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()

# find dependencies
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(turtlesim REQUIRED)

add_executable(navigator src/navigator.cpp)
target_include_directories(navigator PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>)
target_compile_features(navigator PUBLIC c_std_99 cxx_std_17) # Require C99 and C++17
ament_target_dependencies(
navigator
"rclcpp"
"geometry_msgs"
"turtlesim"
)

install(TARGETS navigator
DESTINATION lib/${PROJECT_NAME})

# if(BUILD_TESTING)
# find_package(ament_lint_auto REQUIRED)
# # the following line skips the linter which checks for copyrights
# # comment the line when a copyright and license is added to all source files
# set(ament_cmake_copyright_FOUND TRUE)
# # the following line skips cpplint (only works in a git repo)
# # comment the line when this package is in a git repo and when
# # a copyright and license is added to all source files
# set(ament_cmake_cpplint_FOUND TRUE)
# ament_lint_auto_find_test_dependencies()
# endif()

ament_package()
22 changes: 22 additions & 0 deletions tests/data/pixi_build/ros-workspace/src/navigator/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>navigator</name>
<version>0.0.0</version>
<description>TODO: Package description</description>
<maintainer email="[email protected]">rarts</maintainer>
<license>BSD-3-Clause</license>

<buildtool_depend>ament_cmake</buildtool_depend>

<depend>rclcpp</depend>
<depend>geometry_msgs</depend>
<depend>turtlesim</depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>

<export>
<build_type>ament_cmake</build_type>
</export>
</package>
6 changes: 6 additions & 0 deletions tests/data/pixi_build/ros-workspace/src/navigator/pixi.toml
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
[package.build.backend]
name = "pixi-build-ros"
version = "*"

[package.build.config]
distro = "humble"
Original file line number Diff line number Diff line change
@@ -0,0 +1,94 @@
#define _USE_MATH_DEFINES

#include <cmath>

#include "rclcpp/rclcpp.hpp"
#include "geometry_msgs/msg/point.hpp"
#include "geometry_msgs/msg/twist.hpp"
#include "turtlesim/msg/pose.hpp"

class TurtleNavigator : public rclcpp::Node
{
public:
TurtleNavigator()
: Node("turtle_navigator"), x_goal_(4.0), y_goal_(5.0), kp_(1.0), ki_(0.0), kd_(0.05), prev_error_(0.0), integral_(0.0)
{
subscription_ = this->create_subscription<geometry_msgs::msg::Point>(
"coordinates", 10, std::bind(&TurtleNavigator::goal_callback, this, std::placeholders::_1));
pose_subscription_ = this->create_subscription<turtlesim::msg::Pose>(
"turtle1/pose", 10, std::bind(&TurtleNavigator::pose_callback, this, std::placeholders::_1));
publisher_ = this->create_publisher<geometry_msgs::msg::Twist>("turtle1/cmd_vel", 10);

timer_ = this->create_wall_timer(
std::chrono::milliseconds(100), std::bind(&TurtleNavigator::control_loop, this));

RCLCPP_INFO(this->get_logger(), "Turtle Navigator has been started!");
RCLCPP_INFO(this->get_logger(), "Initial goal: x=%f, y=%f", x_goal_, y_goal_);
}

private:
void goal_callback(const geometry_msgs::msg::Point::SharedPtr msg)
{
x_goal_ = msg->x;
y_goal_ = msg->y;
RCLCPP_INFO(this->get_logger(), "Received goal: x=%f, y=%f", x_goal_, y_goal_);
}

void pose_callback(const turtlesim::msg::Pose::SharedPtr msg)
{
x_current_ = msg->x;
y_current_ = msg->y;
theta_current_ = msg->theta;
}

void control_loop()
{
// RCLCPP_INFO(this->get_logger(), "Hello Ruben!");
double error_x = x_goal_ - x_current_;
double error_y = y_goal_ - y_current_;
double distance_error = std::sqrt(error_x * error_x + error_y * error_y);

double angle_to_goal = std::atan2(error_y, error_x);
double angle_error = angle_to_goal - theta_current_;

// Normalize angle error to the range [-pi, pi]
while (angle_error > M_PI) angle_error -= 2 * M_PI;
while (angle_error < -M_PI) angle_error += 2 * M_PI;

// PID control
double control_signal = kp_ * distance_error + ki_ * integral_ + kd_ * (distance_error - prev_error_);
integral_ += distance_error;
prev_error_ = distance_error;

// Limit control signal
double max_linear_speed = 2.0; // Max linear speed
double max_angular_speed = 2.0; // Max angular speed
control_signal = std::clamp(control_signal, -max_linear_speed, max_linear_speed);

// Publish velocity commands
auto msg = geometry_msgs::msg::Twist();
msg.linear.x = control_signal;
msg.angular.z = 4.0 * angle_error; // simple P controller for angle
msg.angular.z = std::clamp(msg.angular.z, -max_angular_speed, max_angular_speed);

publisher_->publish(msg);
}

rclcpp::Subscription<geometry_msgs::msg::Point>::SharedPtr subscription_;
rclcpp::Subscription<turtlesim::msg::Pose>::SharedPtr pose_subscription_;
rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr publisher_;
rclcpp::TimerBase::SharedPtr timer_;

double x_goal_, y_goal_;
double x_current_, y_current_, theta_current_;
double kp_, ki_, kd_;
double prev_error_, integral_;
};

int main(int argc, char *argv[])
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<TurtleNavigator>());
rclcpp::shutdown();
return 0;
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,89 @@
import rclpy
from rclpy.node import Node
from geometry_msgs.msg import Point, Twist
from turtlesim.msg import Pose
import math


class TurtleNavigator(Node):
def __init__(self):
super().__init__(node_name="turtle_navigator")
self.x_goal = 5.0
self.y_goal = 5.0
self.kp = 1.0
self.ki = 0.0
self.kd = 0.05
self.prev_error = 0.0
self.integral = 0.0

self.subscription = self.create_subscription(Point, "coordinates", self.goal_callback, 10)
self.pose_subscription = self.create_subscription(
Pose, "turtle1/pose", self.pose_callback, 10
)
self.publisher = self.create_publisher(Twist, "turtle1/cmd_vel", 10)

self.timer = self.create_timer(0.1, self.control_loop)

self.x_current = 0.0
self.y_current = 0.0
self.theta_current = 0.0

def goal_callback(self, msg):
self.x_goal = msg.x
self.y_goal = msg.y
self.get_logger().info(f"Received goal: x={self.x_goal}, y={self.y_goal}")

def pose_callback(self, msg):
self.x_current = msg.x
self.y_current = msg.y
self.theta_current = msg.theta

def control_loop(self):
error_x = self.x_goal - self.x_current
error_y = self.y_goal - self.y_current
distance_error = math.sqrt(error_x**2 + error_y**2)

angle_to_goal = math.atan2(error_y, error_x)
angle_error = angle_to_goal - self.theta_current

# Normalize angle error to the range [-pi, pi]
while angle_error > math.pi:
angle_error -= 2 * math.pi
while angle_error < -math.pi:
angle_error += 2 * math.pi

# PID control
control_signal = (
self.kp * distance_error
+ self.ki * self.integral
+ self.kd * (distance_error - self.prev_error)
)
self.integral += distance_error
self.prev_error = distance_error

# Limit control signal
max_linear_speed = 2.0 # Max linear speed
max_angular_speed = 2.0 # Max angular speed
control_signal = max(min(control_signal, max_linear_speed), -max_linear_speed)

# Publish velocity commands
msg = Twist()
msg.linear.x = control_signal
msg.angular.z = 4.0 * angle_error # Simple P controller for angle
msg.angular.z = max(min(msg.angular.z, max_angular_speed), -max_angular_speed)

self.publisher.publish(msg)


def main(args=None):
rclpy.init(args=args)
print("Turtle Navigator")
turtle_navigator = TurtleNavigator()
print("Waiting for command..")
rclpy.spin(turtle_navigator)
turtle_navigator.destroy_node()
rclpy.shutdown()


if __name__ == "__main__":
main()
18 changes: 18 additions & 0 deletions tests/data/pixi_build/ros-workspace/src/navigator_py/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>navigator_py</name>
<version>0.0.0</version>
<description>TODO: Package description</description>
<maintainer email="[email protected]">rubenarts</maintainer>
<license>BSD-3-Clause</license>

<test_depend>ament_copyright</test_depend>
<test_depend>ament_flake8</test_depend>
<test_depend>ament_pep257</test_depend>
<test_depend>python3-pytest</test_depend>

<export>
<build_type>ament_python</build_type>
</export>
</package>
Loading
Loading