Skip to content

Commit 33f16a3

Browse files
authored
Update OpenCR transports & examples (#31)
1 parent ef94672 commit 33f16a3

File tree

5 files changed

+9
-19
lines changed

5 files changed

+9
-19
lines changed

examples/micro-ros_publisher/micro-ros_publisher.ino

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,7 @@ rcl_timer_t timer;
1919
#define LED_PIN 13
2020

2121
#define RCCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){error_loop();}}
22-
#define RCSOFTCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){error_loop();}}
22+
#define RCSOFTCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){}}
2323

2424

2525
void error_loop(){
@@ -83,5 +83,5 @@ void setup() {
8383

8484
void loop() {
8585
delay(100);
86-
RCCHECK(rclc_executor_spin_some(&executor, RCL_MS_TO_NS(100)));
86+
RCSOFTCHECK(rclc_executor_spin_some(&executor, RCL_MS_TO_NS(100)));
8787
}

examples/micro-ros_subscriber/micro-ros_subscriber.ino

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,7 @@ rcl_timer_t timer;
1919
#define LED_PIN 13
2020

2121
#define RCCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){error_loop();}}
22-
#define RCSOFTCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){error_loop();}}
22+
#define RCSOFTCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){}}
2323

2424

2525
void error_loop(){

examples/micro-ros_tf_publisher/micro-ros_tf_publisher.ino

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -25,7 +25,7 @@ rcl_timer_t timer;
2525
#define LED_PIN 13
2626

2727
#define RCCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){error_loop();}}
28-
#define RCSOFTCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){error_loop();}}
28+
#define RCSOFTCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){}}
2929

3030
extern "C" int clock_gettime(clockid_t unused, struct timespec *tp);
3131
cIMU IMU;

extras/library_generation/Dockerfile

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,7 @@ RUN git clone https://github.com/micro-ROS/micro-ros-build.git src/micro-ros-bui
66
&& . /opt/ros/$ROS_DISTRO/setup.sh \
77
&& apt update \
88
&& apt install -y python3-pip wget\
9+
&& apt install -y python3-pip clang-format pyflakes3 python3-mypy python3-pytest-mock gperf ros-foxy-osrf-testing-tools-cpp python3-lttng ros-foxy-mimick-vendor ros-foxy-rmw-cyclonedds-cpp python3-babeltrace \
910
&& rosdep update \
1011
&& rosdep install --from-paths src --ignore-src -y \
1112
&& colcon build \

src/opencr_transports.c.in

Lines changed: 4 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -16,40 +16,29 @@ bool arduino_serial_platform_open()
1616
{
1717
// Place here your initialization platform code
1818
// Return true if success
19+
while(!vcp_is_connected()){}
1920
return vcp_is_connected();
2021
}
2122

2223
bool arduino_serial_platform_close()
2324
{
24-
// Place here your closing platform code
25-
// Return true if success
2625
return true;
27-
2826
}
2927

3028
size_t arduino_serial_platform_write(uint8_t* buf, size_t len, uint8_t* errcode)
3129
{
32-
// Place here your writing bytes platform code
33-
// Return number of bytes written
3430
(void) errcode;
35-
for(size_t i = 0; i < len; i++){
36-
vcp_putch(buf[i]);
37-
while( vcp_is_transmitted() == 0 );
38-
}
39-
40-
return len;
31+
return vcp_write(buf, len);;
4132
}
4233

4334
size_t arduino_serial_platform_read(uint8_t* buf, size_t len, int timeout, uint8_t* errcode)
4435
{
45-
// Place here your reading bytes platform code
46-
// Return number of bytes read (max bytes: len)
4736
(void) errcode;
4837
uint32_t start_time = drv_micros() * 1000;
4938
size_t readed = 0;
5039

51-
while(((drv_micros()*1000) - start_time) < (uint32_t) timeout){
52-
while(vcp_is_available()){
40+
while((readed < len) && (((drv_micros()*1000) - start_time) < (uint32_t) timeout)){
41+
while((readed < len) && vcp_is_available()){
5342
buf[readed++] = vcp_getch();
5443
}
5544
}

0 commit comments

Comments
 (0)