From: Federica Di Lauro Date: Tue, 11 Feb 2020 15:49:50 +0000 (+0100) Subject: receiving velocities command using protobuf X-Git-Url: http://git.leonardobizzoni.com/?a=commitdiff_plain;h=b6c3a952f385156c66a033627a6f83bf2096d1c4;p=pioneer-stm32 receiving velocities command using protobuf --- diff --git a/otto_controller/Core/Src/main.cpp b/otto_controller/Core/Src/main.cpp index e47d2ad..d19ac9f 100644 --- a/otto_controller/Core/Src/main.cpp +++ b/otto_controller/Core/Src/main.cpp @@ -104,7 +104,7 @@ uint8_t *rx_buffer; velocity_msg vel_msg; wheel_msg wheels_msg; -uint8_t mode = 0; //setup mode +int mode = 0; //setup mode uint8_t proto_buffer_rx[50]; pb_istream_t in_pb_stream; @@ -315,30 +315,35 @@ void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim) { void HAL_UART_RxCpltCallback(UART_HandleTypeDef *UartHandle) { + mode++; + float linear_velocity; float angular_velocity; - pb_istream_t stream = pb_istream_from_buffer(proto_buffer_rx, velocity_cmd_length); + pb_istream_t stream = pb_istream_from_buffer(proto_buffer_rx, + velocity_cmd_length); /* Now we are ready to decode the message. */ bool status = pb_decode(&stream, VelocityCommand_fields, &vel_cmd); - linear_velocity = vel_cmd.linear_velocity; - angular_velocity = vel_cmd.angular_velocity; + if (status) { + linear_velocity = vel_cmd.linear_velocity; + angular_velocity = vel_cmd.angular_velocity; - odom.UpdateValues(linear_velocity, angular_velocity); + odom.UpdateValues(linear_velocity, angular_velocity); - float left_setpoint = odom.GetLeftVelocity(); - float right_setpoint = odom.GetRightVelocity(); + float left_setpoint = odom.GetLeftVelocity(); + float right_setpoint = odom.GetRightVelocity(); - left_pid.set(left_setpoint); - right_pid.set(right_setpoint); + left_pid.set(left_setpoint); + right_pid.set(right_setpoint); - float cross_setpoint = left_setpoint - right_setpoint; - cross_pid.set(cross_setpoint); + float cross_setpoint = left_setpoint - right_setpoint; + cross_pid.set(cross_setpoint); + } HAL_UART_Receive_DMA(&huart6, (uint8_t*) &proto_buffer_rx, - velocity_cmd_length); + velocity_cmd_length); } void HAL_GPIO_EXTI_Callback(uint16_t GPIO_Pin) { diff --git a/utils/catkin_ws/src/joypad_bridge/scripts/cmd_vel_transmitter.py b/utils/catkin_ws/src/joypad_bridge/scripts/cmd_vel_transmitter.py index fe9a4a2..36bf463 100755 --- a/utils/catkin_ws/src/joypad_bridge/scripts/cmd_vel_transmitter.py +++ b/utils/catkin_ws/src/joypad_bridge/scripts/cmd_vel_transmitter.py @@ -1,6 +1,7 @@ #!/usr/bin/env python import rospy, serial, struct, time +import otto_communication_pb2 from geometry_msgs.msg import Twist from serial import SerialException @@ -14,10 +15,14 @@ ser = serial.Serial( def callback(data): linear = -data.linear.x angular = -data.angular.z #da fixare? + my_velocity = otto_communication_pb2.VelocityCommand() + my_velocity.linear_velocity = linear; + my_velocity.angular_velocity = angular; rospy.loginfo('I heard %f %f', linear, angular) - msg_output = struct.pack('