Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Redis integration #48

Merged
merged 11 commits into from
Oct 22, 2024
2 changes: 1 addition & 1 deletion .devcontainer/Dockerfile
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ RUN apt-get update \

# Use venv for bluesky and ipython. Will need to call `source /venv/bin/activate`
RUN python3 -m venv venv
RUN . venv/bin/activate && pip install bluesky ophyd Ipython
RUN . venv/bin/activate && pip install bluesky ophyd Ipython redis
ENV DEBIAN_FRONTEND=dialog

# Set up auto-source of workspace for ros user
Expand Down
31 changes: 30 additions & 1 deletion src/aruco_pose/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -45,4 +45,33 @@ In the current implementation, this topic's publish rate is defined in the Azure
## Median estimation
Median pose estimation is a multi-value estimation, where it estimates the median of the 6 DoF pose returned by the camera.

For each DoF, it maintains a moving window of size 10 (can be changed via the parameter `number_of_observations` ) to calculate the median. When the detection rate is 5Hz and upon moving the sample or the detected object to a new pose, it takes a minimum of 1.2 seconds to return the correct pose for the updated pose. As a good practice, it is better to wait for the whole 2 seconds.
For each DoF, it maintains a moving window of size 10 (can be changed via the parameter `number_of_observations` ) to calculate the median. When the detection rate is 5Hz and upon moving the sample or the detected object to a new pose, it takes a minimum of 1.2 seconds to return the correct pose for the updated pose. As a good practice, it is better to wait for the whole 2 seconds.

# Connection to the Redis DB

Redis is used to store the aruco tag ID and real-world sample information. At present, each entry has four properties. They are:
- id -> tag ID of the printed tag from AruCo marker library
- family -> dictionary of tag used [DICT_APRILTAG_36h11, DICT_6X6_250, etc... ]
- size -> physical size of the marker
ChandimaFernando marked this conversation as resolved.
Show resolved Hide resolved
- sample_names -> unique name to identify the sample used with the tag

Run the Redis container with the following command (make sure to have the correct binding for the local storage):
```bash
maffettone marked this conversation as resolved.
Show resolved Hide resolved
podman run --name redis-container --network host -d -v /home/wfernando1/Documents/Environments/Workspaces/redis/data/:/data -p 6379:6379 redis
```

## Insert new entires

Run the following if the command line interface is needed:

```bash
podman exec -it redis-container redis-cli
```

New records can be inserted into the redis server with the following command. Note the below example assumes that each entry has four attributes: id, family, size, and sample_name.

```bash
HSET tag:1 id 0 family "DICT_APRILTAG_36h11" size 0.02665 sample_name sample_1
maffettone marked this conversation as resolved.
Show resolved Hide resolved
```

Same procedure can be found in the file `aruoc_pose/src/redis_insert.py`
16 changes: 16 additions & 0 deletions src/aruco_pose/src/redis_insert.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
"""Copyright 2023 Brookhaven National Laboratory BSD 3 Clause License. See LICENSE.txt for details."""

import redis

# Connect to Redis
# Note: Change the host IP to map your server.
client = redis.Redis(host="192.168.56.1", port=6379, db=0)
maffettone marked this conversation as resolved.
Show resolved Hide resolved

# Step 1: Store tag data in Redis
client.hset("tag:1", mapping={"id": 0, "family": "DICT_APRILTAG_36h11", "size": 0.02665, "sample_name": "sample_1"})

client.hset("tag:2", mapping={"id": 150, "family": "DICT_APRILTAG_36h12", "size": 0.03000, "sample_name": "sample_2"})

# Step 2: Indexing the sample_name to the tag key (e.g., tag:1, tag:2)
client.hset("sample_name_index", "sample_1", "tag:1")
client.hset("sample_name_index", "sample_2", "tag:2")
84 changes: 84 additions & 0 deletions src/pdf_beamtime/src/pdf_beamtime_fidpose_redis_client.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,84 @@
"""Copyright 2023 Brookhaven National Laboratory BSD 3 Clause License. See LICENSE.txt for details."""

import math
import time

import rclpy
from rclpy.action import ActionClient
from rclpy.node import Node

from pdf_beamtime_interfaces.action import FidPoseControlMsg
import redis
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
import rclpy
from rclpy.action import ActionClient
from rclpy.node import Node
from pdf_beamtime_interfaces.action import FidPoseControlMsg
import redis
import rclpy
from rclpy.action import ActionClient
from rclpy.node import Node
import redis
from pdf_beamtime_interfaces.action import FidPoseControlMsg

This should fix the isort.



class SimpleClient(Node):
"""Send a simple goal request to the action server."""

def __init__(self):
"""Python init."""
super().__init__("pdf_beamtime_fidpose_client")
self._action_client = ActionClient(self, FidPoseControlMsg, "pdf_beamtime_fidpose_action_server")
self._goal_handle = None

def send_pickup_goal(self, sample_id):
"""Send a working goal."""
goal_msg = FidPoseControlMsg.Goal()

goal_msg.inbeam_approach = [x / 180 * math.pi for x in [55.10, -51.78, 124.84, -73.16, 52.24, 180.0]]
goal_msg.inbeam = [x / 180 * math.pi for x in [63.84, -47.71, 98.22, -50.59, 61.00, 180.0]]

goal_msg.sample_return = False

goal_msg.sample_id = sample_id

self._action_client.wait_for_server()
self._send_goal_future = self._action_client.send_goal_async(goal_msg, feedback_callback=self.feedback_callback)

def send_return_sample_goal(self, sample_id):
"""Send a working goal."""
goal_msg = FidPoseControlMsg.Goal()

goal_msg.inbeam_approach = [x / 180 * math.pi for x in [55.10, -51.78, 124.84, -73.16, 52.24, 180.0]]
goal_msg.inbeam = [x / 180 * math.pi for x in [63.84, -47.71, 98.22, -50.59, 61.00, 180.0]]

goal_msg.sample_return = True
goal_msg.sample_id = sample_id

self._action_client.wait_for_server()
self._send_goal_future = self._action_client.send_goal_async(goal_msg, feedback_callback=self.feedback_callback)

def feedback_callback(self, feedback_msg):
"""Display the feedback."""
feedback = feedback_msg.feedback
self.get_logger().info("Completion percentage: {0} %".format(math.ceil(feedback.status * 100)))

def goal_response_callback(self, future):
"""Send a cancellation after 15 seconds."""
self._goal_handle = future.result()
time.sleep(15.0)
self.get_logger().warn("********** Goal Canceling Now *********")
self._goal_handle.cancel_goal_async()


def main(args=None):
"""Python main."""
rclpy.init(args=args)

# Change the sample name to represent the correct sample to be picked.
sample_name = "sample_1"

# Read sample ID from the redis server
redis_client = redis.Redis(host="192.168.56.1", port=6379, db=0)
tag_key = redis_client.hget("sample_name_index", sample_name).decode("utf-8")
tag_id = int(redis_client.hget(tag_key, "id"))

client = SimpleClient()
client.send_pickup_goal(tag_id)
# client.send_return_sample_goal(tag_id)

rclpy.spin(client)
client.destroy_node()


if __name__ == "__main__":
main()
Loading