Working on odometry. Got firmware and ros node separating out gps/imu data. Needs to get sent to the right topics, but hard part is done!

This commit is contained in:
2018-07-06 21:48:32 -07:00
parent ecd52aa8a4
commit ddd4953495
7 changed files with 427 additions and 53 deletions

View File

@@ -1,6 +1,10 @@
////////// Includes //////////
#include <ModbusRtu.h>
#include <Adafruit_BNO055_t3.h>
#include <ArduinoJson.h>
#include "FastLED.h"
#include <NMEAGPS.h>
/*
Imu/data (Imu)
@@ -49,13 +53,6 @@ enum HARDWARE {
enum MODBUS_REGISTERS {
DIRECTION = 0, // Input
SPEED = 1, // Input
SLEEP = 2, // Input
CURRENT = 3, // Output
FAULT = 4, // Output
TEMPERATURE = 5 // Output
};
#define GPS_SERIAL_PORT Serial3
@@ -83,11 +80,17 @@ char float_decimal_places = 8;
///// GPS
char current_byte = '$';
String nmea_sentence = "";
char gps_buffer[255];
unsigned char buffer_count = 0;
////////// Class Instantiations //////////
Modbus slave(node_id, mobus_serial_port_number, HARDWARE::COMMS_RS485_EN);
Adafruit_BNO055 bno = Adafruit_BNO055(WIRE_BUS, -1, BNO055_ADDRESS_A, I2C_MASTER, I2C_PINS_18_19, I2C_PULLUP_INT, I2C_RATE_100, I2C_OP_MODE_ISR);
Adafruit_BNO055 bno = Adafruit_BNO055(WIRE_BUS, -1, BNO055_ADDRESS_A, I2C_MASTER, I2C_PINS_18_19, I2C_PULLUP_INT, I2C_RATE_100, I2C_OP_MODE_IMM);
NMEAGPS gps;
const char baud115200[] = "PUBX,41,1,3,3,115200,0";
void setup() {
// Debugging
@@ -122,10 +125,20 @@ void setup() {
}
void loop() {
// Reset JSON for next loop
StaticJsonBuffer<1000> jsonBuffer;
JsonObject& root = jsonBuffer.createObject();
// Do normal polling
poll_modbus();
set_leds();
send_imu_stream_line();
process_gps_and_send_if_ready();
send_imu_stream_line(root);
process_gps_and_send_if_ready(root);
// Print JSON and newline
root.printTo(GPS_IMU_STREAMING_PORT);
GPS_IMU_STREAMING_PORT.println();
}
@@ -145,45 +158,25 @@ void setup_hardware() {
}
void send_imu_stream_line() {
void send_imu_stream_line(JsonObject &root) {
JsonObject& imu_object = root.createNestedObject("imu");
quat = bno.getQuat();
linear_accel = bno.getVector(Adafruit_BNO055::VECTOR_LINEARACCEL);
angular_vel = bno.getVector(Adafruit_BNO055::VECTOR_GYROSCOPE);
GPS_IMU_STREAMING_PORT.print("ox:");
GPS_IMU_STREAMING_PORT.print(quat.x(), float_decimal_places);
GPS_IMU_STREAMING_PORT.print(",");
GPS_IMU_STREAMING_PORT.print("oy:");
GPS_IMU_STREAMING_PORT.print(quat.y(), float_decimal_places);
GPS_IMU_STREAMING_PORT.print(",");
GPS_IMU_STREAMING_PORT.print("oz:");
GPS_IMU_STREAMING_PORT.print(quat.z(), float_decimal_places);
GPS_IMU_STREAMING_PORT.print(",");
GPS_IMU_STREAMING_PORT.print("ow:");
GPS_IMU_STREAMING_PORT.print(quat.w(), float_decimal_places);
imu_object["ox"] = quat.x();
imu_object["oy"] = quat.y();
imu_object["oz"] = quat.z();
imu_object["ow"] = quat.w();
GPS_IMU_STREAMING_PORT.print(",");
GPS_IMU_STREAMING_PORT.print("lax:");
GPS_IMU_STREAMING_PORT.print(linear_accel.x(), float_decimal_places);
GPS_IMU_STREAMING_PORT.print(",");
GPS_IMU_STREAMING_PORT.print("lay:");
GPS_IMU_STREAMING_PORT.print(linear_accel.y(), float_decimal_places);
GPS_IMU_STREAMING_PORT.print(",");
GPS_IMU_STREAMING_PORT.print("laz:");
GPS_IMU_STREAMING_PORT.print(linear_accel.z(), float_decimal_places);
imu_object["lax"] = linear_accel.x();
imu_object["lay"] = linear_accel.y();
imu_object["laz"] = linear_accel.z();
GPS_IMU_STREAMING_PORT.print(",");
GPS_IMU_STREAMING_PORT.print("avx:");
GPS_IMU_STREAMING_PORT.print(angular_vel.x(), float_decimal_places);
GPS_IMU_STREAMING_PORT.print(",");
GPS_IMU_STREAMING_PORT.print("avy:");
GPS_IMU_STREAMING_PORT.print(angular_vel.y(), float_decimal_places);
GPS_IMU_STREAMING_PORT.print(",");
GPS_IMU_STREAMING_PORT.print("avz:");
GPS_IMU_STREAMING_PORT.print(angular_vel.z(), float_decimal_places);
GPS_IMU_STREAMING_PORT.println();
imu_object["avx"] = angular_vel.x();
imu_object["avy"] = angular_vel.y();
imu_object["avz"] = angular_vel.z();
//
// /* Display calibration status for each sensor. */
@@ -199,19 +192,29 @@ void send_imu_stream_line() {
// Serial.print(mag, DEC);
}
void process_gps_and_send_if_ready() {
if (GPS_SERIAL_PORT.available() > 0 ) {
current_byte = GPS_SERIAL_PORT.read();
void process_gps_and_send_if_ready(JsonObject &root) {
root["gps"] = "";
if (current_byte != '\r' && current_byte != '\n') {
nmea_sentence += current_byte;
}
char num_in_bytes = GPS_SERIAL_PORT.available();
if (num_in_bytes > 0) {
for (char i = 0 ; i < num_in_bytes ; i++) {
char in_byte = GPS_SERIAL_PORT.read();
if (in_byte != '\n' && in_byte != '\r') {
gps_buffer[buffer_count] = in_byte;
buffer_count++;
}
if (in_byte == '\r') {
gps_buffer[buffer_count] = '\0';
root["gps"] = gps_buffer;
buffer_count = 0;
}
if (current_byte == '\r') {
GPS_IMU_STREAMING_PORT.println(nmea_sentence);
nmea_sentence = "";
}
}
}
void poll_modbus() {

View File

@@ -27,7 +27,7 @@ enum MODBUS_REGISTERS {
};
////////// Global Variables //////////
const uint8_t node_id = 1;
const uint8_t node_id = 2;
const uint8_t mobus_serial_port_number = 3;
uint16_t modbus_data[] = {0, 0, 0, 0, 0};

View File

@@ -0,0 +1,204 @@
cmake_minimum_required(VERSION 2.8.3)
project(rover_odometry)
## Compile as C++11, supported in ROS Kinetic and newer
# add_compile_options(-std=c++11)
## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
std_msgs
message_generation
)
## System dependencies are found with CMake's conventions
# find_package(Boost REQUIRED COMPONENTS system)
## Uncomment this if the package has a setup.py. This macro ensures
## modules and global scripts declared therein get installed
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
# catkin_python_setup()
################################################
## Declare ROS messages, services and actions ##
################################################
## To declare and build messages, services or actions from within this
## package, follow these steps:
## * Let MSG_DEP_SET be the set of packages whose message types you use in
## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
## * In the file package.xml:
## * add a build_depend tag for "message_generation"
## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET
## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
## but can be declared for certainty nonetheless:
## * add a run_depend tag for "message_runtime"
## * In this file (CMakeLists.txt):
## * add "message_generation" and every package in MSG_DEP_SET to
## find_package(catkin REQUIRED COMPONENTS ...)
## * add "message_runtime" and every package in MSG_DEP_SET to
## catkin_package(CATKIN_DEPENDS ...)
## * uncomment the add_*_files sections below as needed
## and list every .msg/.srv/.action file to be processed
## * uncomment the generate_messages entry below
## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
## Generate messages in the 'msg' folder
# add_message_files(
# FILES
# Message1.msg
# Message2.msg
# )
add_message_files(
FILES
)
## Generate services in the 'srv' folder
# add_service_files(
# FILES
# Service1.srv
# Service2.srv
# )
## Generate actions in the 'action' folder
# add_action_files(
# FILES
# Action1.action
# Action2.action
# )
## Generate added messages and services with any dependencies listed here
generate_messages(
DEPENDENCIES
std_msgs
)
################################################
## Declare ROS dynamic reconfigure parameters ##
################################################
## To declare and build dynamic reconfigure parameters within this
## package, follow these steps:
## * In the file package.xml:
## * add a build_depend and a run_depend tag for "dynamic_reconfigure"
## * In this file (CMakeLists.txt):
## * add "dynamic_reconfigure" to
## find_package(catkin REQUIRED COMPONENTS ...)
## * uncomment the "generate_dynamic_reconfigure_options" section below
## and list every .cfg file to be processed
## Generate dynamic reconfigure parameters in the 'cfg' folder
# generate_dynamic_reconfigure_options(
# cfg/DynReconf1.cfg
# cfg/DynReconf2.cfg
# )
###################################
## catkin specific configuration ##
###################################
## The catkin_package macro generates cmake config files for your package
## Declare things to be passed to dependent projects
## INCLUDE_DIRS: uncomment this if your package contains header files
## LIBRARIES: libraries you create in this project that dependent projects also need
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
# INCLUDE_DIRS include
# LIBRARIES system_statuses
# CATKIN_DEPENDS roscpp rospy std_msgs
# DEPENDS system_lib
)
###########
## Build ##
###########
## Specify additional locations of header files
## Your package locations should be listed before other locations
include_directories(
# include
${catkin_INCLUDE_DIRS}
)
## Declare a C++ library
# add_library(${PROJECT_NAME}
# src/${PROJECT_NAME}/system_statuses.cpp
# )
## Add cmake target dependencies of the library
## as an example, code may need to be generated before libraries
## either from message generation or dynamic reconfigure
# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
## Declare a C++ executable
## With catkin_make all packages are built within a single CMake context
## The recommended prefix ensures that target names across packages don't collide
# add_executable(${PROJECT_NAME}_node src/system_statuses_node.cpp)
## Rename C++ executable without prefix
## The above recommended prefix causes long target names, the following renames the
## target back to the shorter version for ease of user use
## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")
## Add cmake target dependencies of the executable
## same as for the library above
# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
## Specify libraries to link a library or executable target against
# target_link_libraries(${PROJECT_NAME}_node
# ${catkin_LIBRARIES}
# )
#############
## Install ##
#############
# all install targets should use catkin DESTINATION variables
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
## Mark executable scripts (Python etc.) for installation
## in contrast to setup.py, you can choose the destination
# install(PROGRAMS
# scripts/my_python_script
# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
## Mark executables and/or libraries for installation
# install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
## Mark cpp header files for installation
# install(DIRECTORY include/${PROJECT_NAME}/
# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
# FILES_MATCHING PATTERN "*.h"
# PATTERN ".svn" EXCLUDE
# )
## Mark other files for installation (e.g. launch and bag files, etc.)
# install(FILES
# # myfile1
# # myfile2
# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
# )
#############
## Testing ##
#############
## Add gtest based cpp test target and link libraries
# catkin_add_gtest(${PROJECT_NAME}-test test/test_system_statuses.cpp)
# if(TARGET ${PROJECT_NAME}-test)
# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
# endif()
## Add folders to be run by python nosetests
# catkin_add_nosetests(test)

View File

@@ -0,0 +1,68 @@
<?xml version="1.0"?>
<package format="2">
<name>rover_odometry</name>
<version>0.0.0</version>
<description>The rover_tower package</description>
<!-- One maintainer tag required, multiple allowed, one person per tag -->
<!-- Example: -->
<!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
<maintainer email="none@none.com">none</maintainer>
<!-- One license tag required, multiple allowed, one license per tag -->
<!-- Commonly used license strings: -->
<!-- BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
<license>BSD</license>
<!-- Url tags are optional, but multiple are allowed, one per tag -->
<!-- Optional attribute type can be: website, bugtracker, or repository -->
<!-- Example: -->
<!-- <url type="website">http://wiki.ros.org/rover_status</url> -->
<!-- Author tags are optional, multiple are allowed, one per tag -->
<!-- Authors do not have to be maintainers, but could be -->
<!-- Example: -->
<!-- <author email="jane.doe@example.com">Jane Doe</author> -->
<!-- The *depend tags are used to specify dependencies -->
<!-- Dependencies can be catkin packages or system dependencies -->
<!-- Examples: -->
<!-- Use depend as a shortcut for packages that are both build and exec dependencies -->
<!-- <depend>roscpp</depend> -->
<!-- Note that this is equivalent to the following: -->
<!-- <build_depend>roscpp</build_depend> -->
<!-- <exec_depend>roscpp</exec_depend> -->
<!-- Use build_depend for packages you need at compile time: -->
<build_depend>message_generation</build_depend>
<!-- Use build_export_depend for packages you need in order to build against this package: -->
<!-- <build_export_depend>message_generation</build_export_depend> -->
<!-- Use buildtool_depend for build tool packages: -->
<!-- <buildtool_depend>catkin</buildtool_depend> -->
<!-- Use exec_depend for packages you need at runtime: -->
<exec_depend>message_runtime</exec_depend>
<!-- Use test_depend for packages you need only for testing: -->
<!-- <test_depend>gtest</test_depend> -->
<!-- Use doc_depend for packages you need only for building documentation: -->
<!-- <doc_depend>doxygen</doc_depend> -->
<buildtool_depend>catkin</buildtool_depend>
<build_depend>roscpp</build_depend>
<build_depend>rospy</build_depend>
<build_depend>std_msgs</build_depend>
<build_export_depend>roscpp</build_export_depend>
<build_export_depend>rospy</build_export_depend>
<build_export_depend>std_msgs</build_export_depend>
<exec_depend>roscpp</exec_depend>
<exec_depend>rospy</exec_depend>
<exec_depend>std_msgs</exec_depend>
<!-- The export tag contains other, unspecified, tags -->
<export>
<!-- Other tools can request additional information be placed here -->
</export>
</package>

View File

@@ -0,0 +1,98 @@
#!/usr/bin/env python
#####################################
# Imports
#####################################
# Python native imports
import rospy
from time import time, sleep
import json
import serial.rs485
from nmea_msgs.msg import Sentence
#####################################
# Global Variables
#####################################
NODE_NAME = "tower_odometry"
# DEFAULT_PORT = "/dev/rover/ttyOdometry"
DEFAULT_PORT = "/dev/ttyUSB0"
DEFAULT_BAUD = 115200
# DEFAULT_GPS_SENTENCE_TOPIC = "gps/sentence"
DEFAULT_GPS_SENTENCE_TOPIC = "/nmea_sentence"
DEFAULT_DRIVE_CONTROL_STATUS_TOPIC = "drive_status/rear"
DEFAULT_HERTZ = 100
#####################################
# DriveControl Class Definition
#####################################
class Odometry(object):
def __init__(self):
rospy.init_node(NODE_NAME)
self.port = rospy.get_param("~port", DEFAULT_PORT)
self.baud = rospy.get_param("~baud", DEFAULT_BAUD)
self.gps_sentence_topic = rospy.get_param("~gps_sentence_topic", DEFAULT_GPS_SENTENCE_TOPIC)
self.wait_time = 1.0 / rospy.get_param("~hertz", DEFAULT_HERTZ)
self.odom_serial = serial.Serial(port=self.port, baudrate=self.baud)
self.odom_serial.setRTS(0)
self.sentence_publisher = rospy.Publisher(self.gps_sentence_topic, Sentence, queue_size=1)
self.run()
def run(self):
while not rospy.is_shutdown():
start_time = time()
try:
self.process_messages()
except Exception, error:
print "Error occurred:", error
time_diff = time() - start_time
sleep(max(self.wait_time - time_diff, 0))
def process_messages(self):
if self.odom_serial.inWaiting():
line = self.odom_serial.readline() # type:s
# print line
temp = json.loads(line)
gps = temp.get('gps', None)
if gps:
self.broadcast_gps(gps)
imu = temp.get('imu', None)
if imu:
print imu
# if not line.startswith("ox"):
# print line,
# if line[0] == '$':
# print line,
def broadcast_gps(self, gps):
# print gps
self.sentence_publisher.publish(Sentence(sentence=gps))
if __name__ == "__main__":
Odometry()

View File

@@ -14,6 +14,7 @@ folders_to_link=(
zed_wrapper
nimbro_topic_transport
rover_main
rover_odometry
)
# Print heading