Skip to content

Commit

Permalink
Merge pull request #7 from RobRoyce/develop
Browse files Browse the repository at this point in the history
fix: github workflow.
  • Loading branch information
RobRoyce authored Jan 27, 2025
2 parents 4061a02 + a7ef9eb commit 561219c
Show file tree
Hide file tree
Showing 43 changed files with 560 additions and 419 deletions.
17 changes: 12 additions & 5 deletions .github/workflows/publish.yml → .github/workflows/workflow.yml
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
# Rename from publish.yml to workflow.yml to match PyPI's expectation
name: Publish to PyPI

on:
Expand All @@ -23,13 +24,22 @@ jobs:
run: |
python -m pip install --upgrade pip
pip install .[dev]
# Add any ROS mock dependencies needed for tests
pip install empy catkin_pkg rospkg
- name: Run tests
run: pytest

deploy:
needs: test
runs-on: ubuntu-latest
# Add this environment block to match PyPI's trusted publishing
environment:
name: pypi
url: https://pypi.org/p/ros-to-markdown
permissions:
id-token: write # Required for PyPI trusted publishing

steps:
- uses: actions/checkout@v4

Expand All @@ -41,13 +51,10 @@ jobs:
- name: Install dependencies
run: |
python -m pip install --upgrade pip
pip install build twine
pip install build
- name: Build package
run: python -m build

- name: Publish to PyPI
env:
TWINE_USERNAME: __token__
TWINE_PASSWORD: ${{ secrets.PYPI_API_TOKEN }}
run: twine upload dist/*
uses: pypa/gh-action-pypi-publish@release/v1
24 changes: 14 additions & 10 deletions docker/data/ros1_ws/src/action_server/scripts/move_to_goal.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,26 +8,26 @@

class MoveToGoalServer:
def __init__(self):
rospy.init_node('move_to_goal_server', anonymous=True)
rospy.init_node("move_to_goal_server", anonymous=True)
self.server = actionlib.SimpleActionServer(
'/move_to_goal',
MoveToGoalAction,
execute_cb=self.execute_cb,
auto_start=False
"/move_to_goal", MoveToGoalAction, execute_cb=self.execute_cb, auto_start=False
)
self.server.start()

rospy.Subscriber('/environment/data', EnvironmentData, self.env_callback)
rospy.Subscriber("/environment/data", EnvironmentData, self.env_callback)
self.environment_data = None

self.cmd_vel_pub = rospy.Publisher('/cmd_vel', Twist, queue_size=10)
self.cmd_vel_pub = rospy.Publisher("/cmd_vel", Twist, queue_size=10)

def env_callback(self, msg):
self.environment_data = msg

def execute_cb(self, goal):
rospy.loginfo("MoveToGoal: Received goal => target_pose=(%.2f, %.2f)",
goal.target_pose.pose.position.x, goal.target_pose.pose.position.y)
rospy.loginfo(
"MoveToGoal: Received goal => target_pose=(%.2f, %.2f)",
goal.target_pose.pose.position.x,
goal.target_pose.pose.position.y,
)

feedback = MoveToGoalFeedback()
result = MoveToGoalResult()
Expand All @@ -53,9 +53,13 @@ def execute_cb(self, goal):
result.success = True
self.server.set_succeeded(result, "Goal Reached")


def main():
# Keep reference to prevent garbage collection
global node
node = MoveToGoalServer()
rospy.spin()

if __name__ == '__main__':

if __name__ == "__main__":
main()
Empty file.
13 changes: 8 additions & 5 deletions docker/data/ros1_ws/src/data_processing/scripts/data_filter.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,11 +6,11 @@

class DataFilterNode:
def __init__(self):
rospy.init_node('data_filter', anonymous=True)
self.pub_filtered = rospy.Publisher('/data/filtered', FilteredData, queue_size=10)
rospy.init_node("data_filter", anonymous=True)
self.pub_filtered = rospy.Publisher("/data/filtered", FilteredData, queue_size=10)

rospy.Subscriber('/sensor/temperature', Float64, self.temp_callback)
rospy.Subscriber('/sensor/humidity', Float64, self.hum_callback)
rospy.Subscriber("/sensor/temperature", Float64, self.temp_callback)
rospy.Subscriber("/sensor/humidity", Float64, self.hum_callback)

self.temperature = None
self.humidity = None
Expand All @@ -33,9 +33,12 @@ def publish_filtered(self):
self.pub_filtered.publish(filtered)
rospy.loginfo("DataFilter: Published FilteredData")


def main():
global node
node = DataFilterNode()
rospy.spin()

if __name__ == '__main__':

if __name__ == "__main__":
main()
17 changes: 12 additions & 5 deletions docker/data/ros1_ws/src/data_processing/scripts/data_processor.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,18 +6,25 @@

class DataProcessorNode:
def __init__(self):
rospy.init_node('data_processor', anonymous=True)
self.pub_processed = rospy.Publisher('/data/processed', String, queue_size=10)
rospy.Subscriber('/data/filtered', FilteredData, self.filtered_callback)
rospy.init_node("data_processor", anonymous=True)
self.pub_processed = rospy.Publisher("/data/processed", String, queue_size=10)
rospy.Subscriber("/data/filtered", FilteredData, self.filtered_callback)

def filtered_callback(self, msg):
text_out = f"Processed => temp: {msg.temperature:.2f}, hum: {msg.humidity:.2f}, valid: {msg.valid}"
text_out = (
f"Processed => temp: {msg.temperature:.2f}, "
f"hum: {msg.humidity:.2f}, "
f"valid: {msg.valid}"
)
rospy.loginfo("DataProcessor: %s", text_out)
self.pub_processed.publish(text_out)


def main():
global node
node = DataProcessorNode()
rospy.spin()

if __name__ == '__main__':

if __name__ == "__main__":
main()
Original file line number Diff line number Diff line change
Expand Up @@ -6,9 +6,9 @@

class EnvironmentBuilderNode:
def __init__(self):
rospy.init_node('environment_builder', anonymous=True)
self.pub_env = rospy.Publisher('/environment/data', EnvironmentData, queue_size=10)
rospy.Subscriber('/data/processed', String, self.processed_callback)
rospy.init_node("environment_builder", anonymous=True)
self.pub_env = rospy.Publisher("/environment/data", EnvironmentData, queue_size=10)
rospy.Subscriber("/data/processed", String, self.processed_callback)

def processed_callback(self, msg):
env_msg = EnvironmentData()
Expand All @@ -18,9 +18,12 @@ def processed_callback(self, msg):
self.pub_env.publish(env_msg)
rospy.loginfo("EnvironmentBuilder: Published EnvironmentData")


def main():
global node
node = EnvironmentBuilderNode()
rospy.spin()

if __name__ == '__main__':

if __name__ == "__main__":
main()
18 changes: 11 additions & 7 deletions docker/data/ros1_ws/src/robot_control/scripts/move_robot.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,19 +6,23 @@

class MoveRobotNode:
def __init__(self):
rospy.init_node('move_robot', anonymous=True)
rospy.Subscriber('/cmd_vel', Twist, self.cmd_vel_callback)
self.pub_status = rospy.Publisher('/robot/status', String, queue_size=10)
rospy.init_node("move_robot", anonymous=True)
rospy.Subscriber("/cmd_vel", Twist, self.cmd_vel_callback)
self.pub_status = rospy.Publisher("/robot/status", String, queue_size=10)

def cmd_vel_callback(self, cmd):
rospy.loginfo("move_robot: Received cmd_vel linear=%.2f, angular=%.2f",
cmd.linear.x, cmd.angular.z)
status_msg = "MOVING with linear=%.2f, angular=%.2f" % (cmd.linear.x, cmd.angular.z)
rospy.loginfo(
"move_robot: Received cmd_vel linear=%.2f, angular=%.2f", cmd.linear.x, cmd.angular.z
)
status_msg = f"MOVING with linear={cmd.linear.x:.2f}, angular={cmd.angular.z:.2f}"
self.pub_status.publish(status_msg)


def main():
global node
node = MoveRobotNode()
rospy.spin()

if __name__ == '__main__':

if __name__ == "__main__":
main()
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,8 @@


def main():
rospy.init_node('humidity_publisher', anonymous=True)
pub = rospy.Publisher('/sensor/humidity', Float64, queue_size=10)
rospy.init_node("humidity_publisher", anonymous=True)
pub = rospy.Publisher("/sensor/humidity", Float64, queue_size=10)
rate = rospy.Rate(2) # 2Hz

while not rospy.is_shutdown():
Expand All @@ -16,5 +16,6 @@ def main():
pub.publish(humidity_value)
rate.sleep()

if __name__ == '__main__':

if __name__ == "__main__":
main()
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,8 @@


def main():
rospy.init_node('temperature_publisher', anonymous=True)
pub = rospy.Publisher('/sensor/temperature', Float64, queue_size=10)
rospy.init_node("temperature_publisher", anonymous=True)
pub = rospy.Publisher("/sensor/temperature", Float64, queue_size=10)
rate = rospy.Rate(1) # 1Hz

while not rospy.is_shutdown():
Expand All @@ -16,5 +16,6 @@ def main():
pub.publish(temp_value)
rate.sleep()

if __name__ == '__main__':

if __name__ == "__main__":
main()
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,8 @@


def main():
rospy.init_node('conflicting_temperature_publisher', anonymous=True)
pub = rospy.Publisher('/sensor/temperature', Float64, queue_size=10)
rospy.init_node("conflicting_temperature_publisher", anonymous=True)
pub = rospy.Publisher("/sensor/temperature", Float64, queue_size=10)
rate = rospy.Rate(1)

while not rospy.is_shutdown():
Expand All @@ -16,5 +16,6 @@ def main():
pub.publish(temp_value)
rate.sleep()

if __name__ == '__main__':

if __name__ == "__main__":
main()
Original file line number Diff line number Diff line change
Expand Up @@ -8,16 +8,16 @@
def handle_delayed_request(req):
rospy.loginfo("DelayedResponse: Received request. Sleeping 5 seconds...")
time.sleep(5)
return TriggerResponse(
success=True,
message="DelayedResponse done after 5s"
)
return TriggerResponse(success=True, message="DelayedResponse done after 5s")


def main():
rospy.init_node('delayed_response_server', anonymous=True)
s = rospy.Service('/delayed_response', Trigger, handle_delayed_request)
rospy.init_node("delayed_response_server", anonymous=True)
global service
service = rospy.Service("/delayed_response", Trigger, handle_delayed_request)
rospy.loginfo("DelayedResponse: service /delayed_response is ready.")
rospy.spin()

if __name__ == '__main__':

if __name__ == "__main__":
main()
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,8 @@


def main():
rospy.init_node('command_listener', anonymous=True)
pub_cmd_vel = rospy.Publisher('/cmd_vel', Twist, queue_size=10)
rospy.init_node("command_listener", anonymous=True)
pub_cmd_vel = rospy.Publisher("/cmd_vel", Twist, queue_size=10)
rate = rospy.Rate(1)
forward = True

Expand All @@ -24,5 +24,6 @@ def main():
forward = not forward
rate.sleep()

if __name__ == '__main__':

if __name__ == "__main__":
main()
Original file line number Diff line number Diff line change
Expand Up @@ -6,10 +6,12 @@
def data_callback(msg):
rospy.loginfo("VISUALIZE: Received processed data => %s", msg.data)


def main():
rospy.init_node('visualize_data', anonymous=True)
rospy.Subscriber('/data/processed', String, data_callback)
rospy.init_node("visualize_data", anonymous=True)
rospy.Subscriber("/data/processed", String, data_callback)
rospy.spin()

if __name__ == '__main__':

if __name__ == "__main__":
main()
Original file line number Diff line number Diff line change
@@ -1 +1 @@
# Empty init file
# Empty init file
Loading

0 comments on commit 561219c

Please sign in to comment.