Skip to content

Commit 8da95c0

Browse files
committed
Add ros_hwtopic_gateway demo
1 parent 930e9b4 commit 8da95c0

File tree

7 files changed

+452
-0
lines changed

7 files changed

+452
-0
lines changed
Lines changed: 63 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,63 @@
1+
import rclpy
2+
from rclpy.node import Node
3+
4+
import time
5+
import struct
6+
import random
7+
8+
import os
9+
10+
import numpy as np
11+
12+
from cv_bridge import CvBridge
13+
from sensor_msgs.msg import Image
14+
import cv2
15+
from cv_bridge import CvBridge
16+
17+
18+
class ImagePubSub(Node):
19+
20+
def __init__(self):
21+
super().__init__('Image')
22+
23+
self.publisher_ = self.create_publisher(Image, 'inputtopic', 10)
24+
self.cv_image = cv2.imread('image.jpg') ### an RGB image
25+
self.bridge = CvBridge()
26+
self.tstart = 0
27+
self.tend = 0
28+
self.subscription = self.create_subscription(Image,'/topic/gateway',self.listener_callback, 10)
29+
self.subscription # prevent unused variable warning
30+
timer_period = 0.5 # seconds
31+
self.timer = self.create_timer(timer_period, self.timer_callback)
32+
self.msg = self.bridge.cv2_to_imgmsg(np.array(self.cv_image), "bgr8")
33+
self.cnt = 0
34+
35+
36+
def listener_callback(self, msg):
37+
#cv_image = self.bridge.imgmsg_to_cv2(msg, "bgr8")
38+
#cv2.imshow("Image window", cv_image)
39+
#cv2.waitKey(3)
40+
self.tend = time.time()
41+
print('%f' % (self.tend - self.tstart))
42+
self.cnt += 1
43+
exit()
44+
45+
46+
47+
def timer_callback(self):
48+
self.publisher_.publish(self.msg)
49+
print("Data published!")
50+
self.tstart = time.time()
51+
self.timer.cancel()
52+
53+
def main(args=None):
54+
rclpy.init(args=args)
55+
56+
pubsub = ImagePubSub()
57+
rclpy.spin(pubsub)
58+
59+
60+
61+
62+
if __name__ == '__main__':
63+
main()
Lines changed: 63 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,63 @@
1+
import rclpy
2+
from rclpy.node import Node
3+
4+
import time
5+
import struct
6+
import random
7+
8+
import os
9+
10+
import numpy as np
11+
12+
from cv_bridge import CvBridge
13+
from sensor_msgs.msg import Image
14+
import cv2
15+
from cv_bridge import CvBridge
16+
17+
18+
class ImagePubSub(Node):
19+
20+
def __init__(self):
21+
super().__init__('Image')
22+
23+
self.publisher_ = self.create_publisher(Image, '/topic/gateway', 10)
24+
self.cv_image = cv2.imread('image.jpg') ### an RGB image
25+
self.bridge = CvBridge()
26+
self.tstart = 0
27+
self.tend = 0
28+
self.subscription = self.create_subscription(Image,'/outputtopic',self.listener_callback, 10)
29+
self.subscription # prevent unused variable warning
30+
timer_period = 0.5 # seconds
31+
self.timer = self.create_timer(timer_period, self.timer_callback)
32+
self.msg = self.bridge.cv2_to_imgmsg(np.array(self.cv_image), "bgr8")
33+
self.cnt = 0
34+
35+
36+
def listener_callback(self, msg):
37+
#cv_image = self.bridge.imgmsg_to_cv2(msg, "bgr8")
38+
#cv2.imshow("Image window", cv_image)
39+
#cv2.waitKey(3)
40+
self.tend = time.time()
41+
print('%f' % (self.tend - self.tstart))
42+
self.cnt += 1
43+
exit()
44+
45+
46+
47+
def timer_callback(self):
48+
self.publisher_.publish(self.msg)
49+
print("Data published!")
50+
self.tstart = time.time()
51+
self.timer.cancel()
52+
53+
def main(args=None):
54+
rclpy.init(args=args)
55+
56+
pubsub = ImagePubSub()
57+
rclpy.spin(pubsub)
58+
59+
60+
61+
62+
if __name__ == '__main__':
63+
main()
54.8 KB
Loading
Lines changed: 139 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,139 @@
1+
#
2+
# General settings
3+
#
4+
# Name - name of your application
5+
# TargetBoard - board to run your application on
6+
# zedboard
7+
# TargetPart - part to run you application on
8+
# ReferenceDesign - reference design template
9+
# timer
10+
# TargetOS - operating system to use
11+
# linux
12+
# TargetXil - xilinx tools to use
13+
# vivado,2017.1
14+
# vivado,2016.2
15+
# ise,14.7
16+
# TargetHls - HLS synthesis tool to use
17+
# SystemClock - clock of the ReconOS system (defined below)
18+
# CFlags - additional flags for compilation
19+
# LdFlags - additional flags for linking
20+
#
21+
[General]
22+
Name = SortDemo
23+
TargetBoard = zcu104,0
24+
TargetPart = xczu7ev-ffvc1156-2-e
25+
CPUArchitecture = arm64
26+
ROS2Distribution = galactic
27+
ReferenceDesign = hwtopics
28+
TargetOS = linux64
29+
TargetXil = vivado,2021.2
30+
TargetHls = vivado,2021.2
31+
SystemClock = System
32+
#CFlags = -I $(RECONOS)/linux/tools/timer
33+
#LdFlags = -L $(RECONOS)/linux/tools/timer -ltimer
34+
35+
36+
TargetBoardAddress = 131.234.250.144
37+
#TargetBoardAddress = 192.168.188.90
38+
#TargetBoardAddress = 192.168.2.99
39+
40+
TargetBoardUser = root
41+
TargetBoardPassword = xilinx
42+
43+
44+
#
45+
# Clock definition [Clock@<clock_name>]
46+
#
47+
# ClockSource - static or dynamic clock
48+
# static
49+
# dynamic
50+
# ClockFreq - initial clock frequency
51+
#
52+
[Clock@System]
53+
ClockSource = static
54+
ClockFreq = 100000000
55+
56+
57+
#
58+
# Specification of hardware thread slots [Thread@<slot_name>(<id_range>)]
59+
#
60+
# Id - id of the slot
61+
# Clock - clock connected to the slot
62+
#
63+
64+
[HwSlot@SlotThreada(0:0)]
65+
Id = 0
66+
Clock = System
67+
68+
[HwSlot@SlotThreadb(0:0)]
69+
Id = 1
70+
Clock = System
71+
72+
[HwSlot@Gateways(0:0)]
73+
Id = 2
74+
Clock = System
75+
76+
#
77+
# Resource definition [ResourceGroup@<group_name>]
78+
#
79+
# <resource_name> - type,<optional arguments>
80+
#
81+
82+
[ResourceGroup@RThread0]
83+
tmp = mbox, 128
84+
85+
[ResourceGroup@RThreada]
86+
debug_mbox = mbox, 128
87+
img_output = rosmsg, sensor_msgs ,msg ,Image
88+
node_1 = rosnode, "nodeofthread2"
89+
PubData = rospub, node_1,img_output, "/outputtopic"
90+
SubData = rossub, node_1,sensor_msgs/Image, "nicehwtopic", hw
91+
92+
[ResourceGroup@RThreadb]
93+
img_input = rosmsg, sensor_msgs ,msg ,Image
94+
node_1 = rosnode, "nodeofthread1"
95+
SubData = rossub, node_1, img_input, "/inputtopic", 10000
96+
PubData = rospub, node_1, sensor_msgs/Image, "nicehwtopic", hw
97+
98+
[ResourceGroup@RThreadc]
99+
img_output = rosmsg, sensor_msgs ,msg ,Image
100+
node_1 = rosnode, "nodeofthread3"
101+
PubData = rospub, node_1, img_output, "outputtopic"
102+
SubData = rossub, node_1, sensor_msgs/Image, "nicehwtopic", hw
103+
104+
105+
#
106+
# Specification of thread types [ReconosThread@<thread_name>]
107+
#
108+
# Slot - slot to implement the hardware thread in
109+
# <slot_name>(<id>)
110+
# HwSource - source of the hardware thread
111+
# vhdl
112+
# hls
113+
# SwSource - source of the software thread
114+
# c
115+
# ResourceGroup - resources of the hardware thread
116+
# <group_name>
117+
#
118+
119+
120+
[ReconosThread@Threada]
121+
Slot = SlotThreada(*)
122+
HwSource = hls
123+
ResourceGroup = RThreada
124+
125+
126+
[ReconosThread@Threadb]
127+
Slot = SlotThreadb(*)
128+
HwSource = hls
129+
ResourceGroup = RThreadb
130+
131+
132+
133+
134+
135+
[ROSGateway@Gateway1]
136+
Slot = Gateways(0)
137+
HWTopic = "nicehwtopic"
138+
SWTopic = "/topic/gateway"
139+
MsgType = sensor_msgs/Image
Lines changed: 81 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,81 @@
1+
#include "reconos.h"
2+
#include "reconos_app.h"
3+
#include "mbox.h"
4+
5+
#include <stdio.h>
6+
#include <stdlib.h>
7+
#include <string.h>
8+
#include <unistd.h>
9+
10+
11+
#define DEFAULT_IMAGE_HEIGHT 1000
12+
#define DEFAULT_IMAGE_WIDTH 1000
13+
14+
15+
16+
#define log(...) printf(__VA_ARGS__); fflush(stdout)
17+
18+
19+
20+
int main(int argc, char **argv) {
21+
22+
printf("Start init \n");
23+
24+
reconos_init();
25+
reconos_app_init();
26+
27+
28+
// gateway image
29+
30+
rthreada_img_output->header.frame_id.data=malloc(DEFAULT_IMAGE_HEIGHT*DEFAULT_IMAGE_WIDTH*3);
31+
rthreada_img_output->encoding.data = malloc(DEFAULT_IMAGE_HEIGHT*DEFAULT_IMAGE_WIDTH*3);
32+
rthreada_img_output->data.data = malloc(DEFAULT_IMAGE_HEIGHT*DEFAULT_IMAGE_WIDTH*3);
33+
34+
gateway1_ressourcegroup_msg_out->header.frame_id.data=malloc(DEFAULT_IMAGE_HEIGHT*DEFAULT_IMAGE_WIDTH*3);
35+
gateway1_ressourcegroup_msg_out->encoding.data = malloc(DEFAULT_IMAGE_HEIGHT*DEFAULT_IMAGE_WIDTH*3);
36+
gateway1_ressourcegroup_msg_out->data.data = malloc(DEFAULT_IMAGE_HEIGHT*DEFAULT_IMAGE_WIDTH*3);
37+
38+
39+
memset(rthreada_img_output->header.frame_id.data, 0, DEFAULT_IMAGE_HEIGHT*DEFAULT_IMAGE_WIDTH*3);
40+
memset(rthreada_img_output->encoding.data, 0, DEFAULT_IMAGE_HEIGHT*DEFAULT_IMAGE_WIDTH*3);
41+
memset(rthreada_img_output->data.data, 0, DEFAULT_IMAGE_HEIGHT*DEFAULT_IMAGE_WIDTH*3);
42+
43+
memset(gateway1_ressourcegroup_msg_out->header.frame_id.data, 0, DEFAULT_IMAGE_HEIGHT*DEFAULT_IMAGE_WIDTH*3);
44+
memset(gateway1_ressourcegroup_msg_out->encoding.data, 0, DEFAULT_IMAGE_HEIGHT*DEFAULT_IMAGE_WIDTH*3);
45+
memset(gateway1_ressourcegroup_msg_out->data.data, 0, DEFAULT_IMAGE_HEIGHT*DEFAULT_IMAGE_WIDTH*3);
46+
47+
reconos_thread_create_hwt_threada(0);
48+
reconos_thread_create_hwt_threadb(0);
49+
50+
reconos_thread_create_hwt_gateway1(0);
51+
52+
ros_subscriber_set_publishfilter(gateway1_ressourcegroup_sub, gateway1_ressourcegroup_pub->guid);
53+
54+
while(1)
55+
{
56+
sleep(1);
57+
58+
//ros_subscriber_message_take(gateway1_ressourcegroup_sub, gateway1_ressourcegroup_msg_in);
59+
//printf("Message arrived! \n");
60+
//printf("size = %d, data = %x \n", gateway1_ressourcegroup_msg_in->encoding.size, gateway1_ressourcegroup_msg_in->encoding.data);
61+
62+
//uint32_t val = mbox_get(rthreada_debug_mbox);
63+
//printf("Message arrived! \n");
64+
65+
// printf("gateway1_ressourcegroup_msg_out->height = %d \n", rthreada_img_output->height);
66+
// printf("gateway1_ressourcegroup_msg_out->width = %d \n", rthreada_img_output->width);
67+
68+
// printf("gateway1_ressourcegroup_msg_out->encoding.data = %s \n", rthreada_img_output->encoding.data);
69+
// printf("gateway1_ressourcegroup_msg_out->encoding.size = %d \n", rthreada_img_output->encoding.size);
70+
// printf("gateway1_ressourcegroup_msg_out->encoding.capacity = %d \n", rthreada_img_output->encoding.capacity);
71+
// printf("gateway1_ressourcegroup_msg_out->header.frame_id.data = %s \n", rthreada_img_output->header.frame_id.data);
72+
// printf("gateway1_ressourcegroup_msg_out->header.frame_id.size = %d \n", rthreada_img_output->header.frame_id.size);
73+
// printf("gateway1_ressourcegroup_msg_out->header.frame_id.capacity = %d \n", rthreada_img_output->header.frame_id.capacity);
74+
75+
}
76+
77+
reconos_app_cleanup();
78+
reconos_cleanup();
79+
80+
return 0;
81+
}

0 commit comments

Comments
 (0)