final
This commit is contained in:
parent
a4892c2658
commit
89607ceea2
|
|
@ -0,0 +1,335 @@
|
|||
#include <Wire.h>
|
||||
#include <Adafruit_BNO055.h>
|
||||
|
||||
#include <avr/wdt.h>
|
||||
#include <EEPROM.h>
|
||||
|
||||
#define BUFFER_LENGTH 128
|
||||
#define BNO_POWER_PIN 10
|
||||
#define BNO055_SAMPLERATE_DELAY_MS 10 //100Hz for Fusion mode
|
||||
|
||||
Adafruit_BNO055 bno = Adafruit_BNO055(55);
|
||||
int eeAddress = 0;
|
||||
|
||||
void reset() {
|
||||
do {
|
||||
wdt_enable(WDTO_15MS);
|
||||
for(;;);
|
||||
} while(0);
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
void displaySensorStatus(void)
|
||||
{
|
||||
/* Get the system status values (mostly for debugging purposes) */
|
||||
uint8_t system_status, self_test_results, system_error;
|
||||
system_status = self_test_results = system_error = 0;
|
||||
bno.getSystemStatus(&system_status, &self_test_results, &system_error);
|
||||
|
||||
/* Display the results in the Serial Monitor */
|
||||
Serial.println("");
|
||||
Serial.print("System Status: 0x");
|
||||
Serial.println(system_status, HEX);
|
||||
Serial.print("Self Test: 0x");
|
||||
Serial.println(self_test_results, HEX);
|
||||
Serial.print("System Error: 0x");
|
||||
Serial.println(system_error, HEX);
|
||||
Serial.println("");
|
||||
delay(500);
|
||||
}
|
||||
|
||||
/**************************************************************************/
|
||||
/*
|
||||
Display sensor calibration status
|
||||
*/
|
||||
/**************************************************************************/
|
||||
void displayCalStatus(void)
|
||||
{
|
||||
/* Get the four calibration values (0..3) */
|
||||
/* Any sensor data reporting 0 should be ignored, */
|
||||
/* 3 means 'fully calibrated" */
|
||||
uint8_t system, gyro, accel, mag;
|
||||
system = gyro = accel = mag = 0;
|
||||
bno.getCalibration(&system, &gyro, &accel, &mag);
|
||||
|
||||
/* The data should be ignored until the system calibration is > 0 */
|
||||
Serial.print("\t");
|
||||
if (!system)
|
||||
{
|
||||
Serial.print("! ");
|
||||
}
|
||||
|
||||
/* Display the individual values */
|
||||
Serial.print("Sys:");
|
||||
Serial.print(system, DEC);
|
||||
Serial.print(" G:");
|
||||
Serial.print(gyro, DEC);
|
||||
Serial.print(" A:");
|
||||
Serial.print(accel, DEC);
|
||||
Serial.print(" M:");
|
||||
Serial.print(mag, DEC);
|
||||
}
|
||||
|
||||
/**************************************************************************/
|
||||
/*
|
||||
Display the raw calibration offset and radius data
|
||||
*/
|
||||
/**************************************************************************/
|
||||
void displaySensorOffsets(const adafruit_bno055_offsets_t &calibData)
|
||||
{
|
||||
Serial.print("Accelerometer: ");
|
||||
Serial.print(calibData.accel_offset_x); Serial.print(" ");
|
||||
Serial.print(calibData.accel_offset_y); Serial.print(" ");
|
||||
Serial.print(calibData.accel_offset_z); Serial.print(" ");
|
||||
|
||||
Serial.print("\nGyro: ");
|
||||
Serial.print(calibData.gyro_offset_x); Serial.print(" ");
|
||||
Serial.print(calibData.gyro_offset_y); Serial.print(" ");
|
||||
Serial.print(calibData.gyro_offset_z); Serial.print(" ");
|
||||
|
||||
Serial.print("\nMag: ");
|
||||
Serial.print(calibData.mag_offset_x); Serial.print(" ");
|
||||
Serial.print(calibData.mag_offset_y); Serial.print(" ");
|
||||
Serial.print(calibData.mag_offset_z); Serial.print(" ");
|
||||
|
||||
Serial.print("\nAccel Radius: ");
|
||||
Serial.print(calibData.accel_radius);
|
||||
|
||||
Serial.print("\nMag Radius: ");
|
||||
Serial.print(calibData.mag_radius);
|
||||
}
|
||||
|
||||
|
||||
int zeros = 0;
|
||||
void readBufSend(){
|
||||
byte buf0[45];
|
||||
byte buf1[45];
|
||||
byte buf2[45];
|
||||
|
||||
bno.readLen(bno.BNO055_CHIP_ID_ADDR, buf0, 8);
|
||||
bno.readLen(bno.BNO055_ACCEL_DATA_X_LSB_ADDR, buf1, 24);
|
||||
bno.readLen(bno.BNO055_QUATERNION_DATA_W_LSB_ADDR, buf2, 22);
|
||||
|
||||
// Check if first few bytes are zeros;
|
||||
// TODO: Improve this method
|
||||
if((int)(buf1[0]+buf1[1]+buf1[2]+buf1[3]+buf1[4]+buf1[5]+buf1[6]+buf1[7]+buf1[8])==(int)0) {
|
||||
zeros++;
|
||||
if(zeros > 128) {
|
||||
Serial.println("# bad data, resetting in 1s");
|
||||
delay(1000);
|
||||
reset();
|
||||
}
|
||||
} else {
|
||||
zeros = 0;
|
||||
// Read registers QUATERNION_DATA_W_LSB to CALIB_STAT
|
||||
Serial.write((byte)0xF0);
|
||||
Serial.write((byte)0xF0);
|
||||
Serial.write((byte)0xF0);
|
||||
Serial.write((byte)0xF0);
|
||||
Serial.write(buf0, 8);
|
||||
Serial.write(buf1, 24);
|
||||
Serial.write(buf2, 22);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/// @fullcalib: 1: Calibrate Mag,Acc&Gyro; 0: Mag only
|
||||
int calibrate(bool fullcalib){
|
||||
// Calibration routine
|
||||
delay(100); // Sleep for 100ms
|
||||
// Loop until Calibration is Success
|
||||
long bnoID;
|
||||
sensor_t sensor;
|
||||
bno.getSensor(&sensor);
|
||||
sensors_event_t event;
|
||||
bno.getEvent(&event);
|
||||
if (!fullcalib){
|
||||
Serial.println("Move sensor slightly to calibrate magnetometers");
|
||||
while (!bno.isFullyCalibrated())
|
||||
{
|
||||
bno.getEvent(&event);
|
||||
delay(BNO055_SAMPLERATE_DELAY_MS);
|
||||
// displayCalStatus();Serial.println();
|
||||
readBufSend();
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
Serial.println("Please Calibrate Sensor: ");
|
||||
while (!bno.isFullyCalibrated())
|
||||
{
|
||||
bno.getEvent(&event);
|
||||
|
||||
Serial.print("X: ");
|
||||
Serial.print(event.orientation.x, 4);
|
||||
Serial.print("\tY: ");
|
||||
Serial.print(event.orientation.y, 4);
|
||||
Serial.print("\tZ: ");
|
||||
Serial.print(event.orientation.z, 4);
|
||||
|
||||
/* Optional: Display calibration status */
|
||||
displayCalStatus();
|
||||
|
||||
/* New line for the next sample */
|
||||
Serial.println("");
|
||||
|
||||
/* Wait the specified delay before requesting new data */
|
||||
delay(BNO055_SAMPLERATE_DELAY_MS);
|
||||
}
|
||||
}
|
||||
|
||||
Serial.println("\nFully calibrated!");
|
||||
Serial.println("--------------------------------");
|
||||
Serial.println("Calibration Results: ");
|
||||
adafruit_bno055_offsets_t newCalib;
|
||||
bno.getSensorOffsets(newCalib);
|
||||
displaySensorOffsets(newCalib);
|
||||
Serial.println("\n\nStoring calibration data to EEPROM...");
|
||||
|
||||
eeAddress = 0;
|
||||
bno.getSensor(&sensor);
|
||||
bnoID = sensor.sensor_id;
|
||||
EEPROM.put(eeAddress, bnoID);
|
||||
eeAddress += sizeof(long);
|
||||
EEPROM.put(eeAddress, newCalib);
|
||||
Serial.println("Data stored to EEPROM.");
|
||||
Serial.println("\n--------------------------------\n");
|
||||
delay(500);
|
||||
}
|
||||
|
||||
void setup_bno(){
|
||||
uint8_t unitsel = (0 << 7) | // Orientation = Android
|
||||
(0 << 4) | // Temperature = Celsius
|
||||
(0 << 2) | // Euler = Degrees
|
||||
(1 << 1) | // Gyro = Rads
|
||||
(0 << 0); // Accelerometer = m/s^2
|
||||
// Rest the system:
|
||||
bno.setMode(bno.OPERATION_MODE_CONFIG);
|
||||
// Reset
|
||||
bno.write8(bno.BNO055_SYS_TRIGGER_ADDR, 0x20);
|
||||
while (bno.read8(bno.BNO055_CHIP_ID_ADDR) != 0xA0)
|
||||
{
|
||||
delay(50);
|
||||
Serial.println("Waiting for BNO to start...");
|
||||
}
|
||||
delay(50);
|
||||
bno.write8(bno.BNO055_PWR_MODE_ADDR, bno.POWER_MODE_NORMAL); delay(10);
|
||||
// Write Data to Page: 0
|
||||
bno.write8(bno.BNO055_PAGE_ID_ADDR, 0); delay(10);
|
||||
bno.setMode(bno.OPERATION_MODE_CONFIG); delay(25);
|
||||
bno.write8(bno.BNO055_UNIT_SEL_ADDR, unitsel);
|
||||
bno.write8(bno.BNO055_AXIS_MAP_CONFIG_ADDR, bno.REMAP_CONFIG_P1); delay(10); // P0-P7, Default is P1
|
||||
bno.write8(bno.BNO055_AXIS_MAP_SIGN_ADDR, bno.REMAP_SIGN_P1); delay(10); // P0-P7, Default is P1
|
||||
bno.write8(bno.BNO055_SYS_TRIGGER_ADDR, 0x0); delay(10);
|
||||
bno.setMode(bno.OPERATION_MODE_NDOF); delay(200);
|
||||
long bnoID;
|
||||
bool foundCalib = false;
|
||||
|
||||
EEPROM.get(eeAddress, bnoID);
|
||||
|
||||
adafruit_bno055_offsets_t calibrationData;
|
||||
sensor_t sensor;
|
||||
/*
|
||||
* Look for the sensor's unique ID at the beginning oF EEPROM.
|
||||
* This isn't foolproof, but it's better than nothing.
|
||||
*/
|
||||
bno.getSensor(&sensor);
|
||||
if (bnoID != sensor.sensor_id)
|
||||
{
|
||||
Serial.println("\nNo Calibration Data for this sensor exists in EEPROM");
|
||||
delay(500);
|
||||
}
|
||||
else
|
||||
{
|
||||
Serial.println("\nFound Calibration for this sensor in EEPROM.");
|
||||
eeAddress += sizeof(long);
|
||||
EEPROM.get(eeAddress, calibrationData);
|
||||
displaySensorOffsets(calibrationData);
|
||||
Serial.println("\n\nRestoring Calibration data to the BNO055...");
|
||||
bno.setSensorOffsets(calibrationData);
|
||||
Serial.println("\n\nCalibration data loaded into BNO055");
|
||||
foundCalib = true;
|
||||
}
|
||||
delay(1000);
|
||||
/* Display some basic information on this sensor */
|
||||
displaySensorDetails();
|
||||
/* Optional: Display current status */
|
||||
displaySensorStatus();
|
||||
// Set External Crystal
|
||||
bno.setExtCrystalUse(true);
|
||||
}
|
||||
void bno_chip_power_reset(){
|
||||
Serial.println("# BNO055 power off");
|
||||
digitalWrite(BNO_POWER_PIN, LOW);
|
||||
delay(500);
|
||||
Serial.println("# BNO055 power on");
|
||||
digitalWrite(BNO_POWER_PIN, HIGH);
|
||||
|
||||
}
|
||||
|
||||
void setup(void) {
|
||||
wdt_disable();
|
||||
delay(1000);
|
||||
Serial.begin(115200);
|
||||
// BNO Power pin:
|
||||
pinMode(BNO_POWER_PIN, OUTPUT);
|
||||
|
||||
delay(200);
|
||||
// Chip power reset
|
||||
bno_chip_power_reset();
|
||||
delay(500);
|
||||
|
||||
Serial.println("# Check if sensor is connected:");
|
||||
if(!bno.begin(bno.OPERATION_MODE_CONFIG))
|
||||
{
|
||||
Serial.println("# no BNO055 detected");
|
||||
delay(100);
|
||||
reset();
|
||||
}
|
||||
setup_bno();
|
||||
delay(1000);
|
||||
}
|
||||
|
||||
|
||||
void loop(void) {
|
||||
byte b;
|
||||
if(Serial.available()) {
|
||||
b = Serial.read();
|
||||
switch(b) {
|
||||
case 'R' :
|
||||
// Reset the IMU setup
|
||||
delay(100);
|
||||
bno_chip_power_reset(); // This will power down the BNO for some time
|
||||
delay(200);
|
||||
if(!bno.begin(bno.OPERATION_MODE_CONFIG))
|
||||
{
|
||||
Serial.println("# no BNO055 detected");
|
||||
delay(100);
|
||||
reset();
|
||||
}
|
||||
setup_bno();
|
||||
delay(1000);
|
||||
break;
|
||||
case 'M':
|
||||
// Calibrate Magnetometer (Can be done from ROS node)
|
||||
calibrate(false);
|
||||
break;
|
||||
case 'F':
|
||||
// Complete Calibration. (Has to be done when IMU is outside the robot)
|
||||
calibrate(true);
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
// Read the buffers when sensor data is ready
|
||||
sensors_event_t event;
|
||||
bno.getEvent(&event);
|
||||
// Read the buffers and send over serial
|
||||
readBufSend();
|
||||
|
||||
delay(BNO055_SAMPLERATE_DELAY_MS);
|
||||
}
|
||||
|
|
@ -0,0 +1,20 @@
|
|||
cmake_minimum_required(VERSION 2.8.3)
|
||||
project(imu_bno055_arduino)
|
||||
|
||||
find_package(catkin REQUIRED COMPONENTS roscpp sensor_msgs std_msgs serial)
|
||||
|
||||
catkin_package(INCLUDE_DIRS include)
|
||||
|
||||
include_directories(include ${catkin_INCLUDE_DIRS})
|
||||
|
||||
add_executable(imu_bno055_node src/imu_bno055_node.cpp src/BNO055Activity.cpp)
|
||||
|
||||
include_directories(${catkin_INCLUDE_DIRS})
|
||||
|
||||
target_link_libraries(imu_bno055_node ${catkin_LIBRARIES})
|
||||
|
||||
install(TARGETS imu_bno055_node
|
||||
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
|
||||
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
|
||||
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
|
||||
)
|
||||
|
|
@ -0,0 +1,42 @@
|
|||
#ifndef _BNO055Activity_hpp
|
||||
#define _BNO055Activity_hpp
|
||||
|
||||
#include <ros/ros.h>
|
||||
#include <sensor_msgs/Imu.h>
|
||||
#include <sensor_msgs/MagneticField.h>
|
||||
#include <sensor_msgs/Temperature.h>
|
||||
#include "serial/serial.h"
|
||||
|
||||
namespace imu_bno055 {
|
||||
|
||||
class BNO055Activity {
|
||||
public:
|
||||
BNO055Activity(ros::NodeHandle &_nh, ros::NodeHandle &_nh_priv);
|
||||
|
||||
bool open();
|
||||
void close();
|
||||
bool start();
|
||||
void stop();
|
||||
bool spinOnce();
|
||||
|
||||
private:
|
||||
bool isOpen() const;
|
||||
|
||||
std::string frame_id;
|
||||
std::string port;
|
||||
int baud;
|
||||
int seq;
|
||||
|
||||
serial::Serial ser;
|
||||
ros::NodeHandle nh;
|
||||
ros::NodeHandle nh_priv;
|
||||
ros::Publisher pub_data;
|
||||
ros::Publisher pub_raw;
|
||||
ros::Publisher pub_mag;
|
||||
ros::Publisher pub_temp;
|
||||
};
|
||||
|
||||
}
|
||||
|
||||
#endif /* _BNO055Activity_hpp */
|
||||
|
||||
|
|
@ -0,0 +1,15 @@
|
|||
<?xml version="1.0"?>
|
||||
<package>
|
||||
<name>imu_bno055_arduino</name>
|
||||
<version>0.0.0</version>
|
||||
<description>imu</description>
|
||||
<maintainer >Zeek</maintainer>
|
||||
<license>ECAM</license>
|
||||
<buildtool_depend>catkin</buildtool_depend>
|
||||
<build_depend>rospy</build_depend>
|
||||
<build_depend>std_msgs</build_depend>
|
||||
<run_depend>rospy</run_depend>
|
||||
<run_depend>std_msgs</run_depend>
|
||||
<export>
|
||||
</export>
|
||||
</package>
|
||||
|
|
@ -0,0 +1,22 @@
|
|||
{
|
||||
"configurations": [
|
||||
{
|
||||
"browse": {
|
||||
"databaseFilename": "${default}",
|
||||
"limitSymbolsToIncludedHeaders": false
|
||||
},
|
||||
"includePath": [
|
||||
"/opt/ros/noetic/include/**",
|
||||
"/home/hour/agv_ws/src/agv_controller/include/**",
|
||||
"/home/hour/agv_ws/src/imu/include/**",
|
||||
"/usr/include/**"
|
||||
],
|
||||
"name": "ROS",
|
||||
"intelliSenseMode": "gcc-x64",
|
||||
"compilerPath": "/usr/bin/gcc",
|
||||
"cStandard": "gnu11",
|
||||
"cppStandard": "c++14"
|
||||
}
|
||||
],
|
||||
"version": 4
|
||||
}
|
||||
|
|
@ -0,0 +1,8 @@
|
|||
{
|
||||
"python.autoComplete.extraPaths": [
|
||||
"/opt/ros/noetic/lib/python3/dist-packages"
|
||||
],
|
||||
"python.analysis.extraPaths": [
|
||||
"/opt/ros/noetic/lib/python3/dist-packages"
|
||||
]
|
||||
}
|
||||
|
|
@ -0,0 +1,189 @@
|
|||
#include "imu_bno055/BNO055Activity.hpp"
|
||||
|
||||
#include <cstdlib>
|
||||
#include <cerrno>
|
||||
#include <cstring>
|
||||
#include <fcntl.h>
|
||||
#include <termios.h>
|
||||
|
||||
// 54 bytes
|
||||
typedef struct {
|
||||
int8_t chip_id_bno055;
|
||||
int8_t chip_id_acc;
|
||||
int8_t chip_id_mag;
|
||||
int8_t chip_id_gyro;
|
||||
int16_t sw_revision_id;
|
||||
int8_t bootloader_version;
|
||||
int8_t page_id;
|
||||
int16_t raw_linear_acceleration_x;
|
||||
int16_t raw_linear_acceleration_y;
|
||||
int16_t raw_linear_acceleration_z;
|
||||
int16_t raw_magnetic_field_x;
|
||||
int16_t raw_magnetic_field_y;
|
||||
int16_t raw_magnetic_field_z;
|
||||
int16_t raw_angular_velocity_x;
|
||||
int16_t raw_angular_velocity_y;
|
||||
int16_t raw_angular_velocity_z;
|
||||
int16_t fused_heading;
|
||||
int16_t fused_roll;
|
||||
int16_t fused_pitch;
|
||||
int16_t fused_orientation_w;
|
||||
int16_t fused_orientation_x;
|
||||
int16_t fused_orientation_y;
|
||||
int16_t fused_orientation_z;
|
||||
int16_t fused_linear_acceleration_x;
|
||||
int16_t fused_linear_acceleration_y;
|
||||
int16_t fused_linear_acceleration_z;
|
||||
int16_t gravity_vector_x;
|
||||
int16_t gravity_vector_y;
|
||||
int16_t gravity_vector_z;
|
||||
int8_t temperature;
|
||||
int8_t calibration_status;
|
||||
} imu_record;
|
||||
|
||||
namespace imu_bno055 {
|
||||
|
||||
BNO055Activity::BNO055Activity( ros::NodeHandle &_nh, ros::NodeHandle &_nh_priv ) :
|
||||
port(""),
|
||||
nh(_nh),
|
||||
seq(0),
|
||||
nh_priv( _nh_priv )
|
||||
{
|
||||
ROS_INFO("initializing");
|
||||
nh_priv.param( "port", port, (std::string)"/dev/ttyACM0" );
|
||||
nh_priv.param( "baud", baud, (int)115200 );
|
||||
nh_priv.param( "frame_id", frame_id, (std::string)"imu" );
|
||||
}
|
||||
|
||||
bool BNO055Activity::open() {
|
||||
try {
|
||||
ser.setPort(port);
|
||||
ser.setBaudrate(baud);
|
||||
serial::Timeout to = serial::Timeout::simpleTimeout(1000);
|
||||
ser.setTimeout(to);
|
||||
ser.open();
|
||||
} catch(serial::IOException& e) {
|
||||
ROS_ERROR_STREAM("cannot open serial port");
|
||||
exit(EXIT_FAILURE);
|
||||
}
|
||||
|
||||
if(!ser.isOpen()) {
|
||||
ROS_ERROR_STREAM("cannot open serial port");
|
||||
exit(EXIT_FAILURE);
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void BNO055Activity::close() {
|
||||
ROS_INFO("closing port");
|
||||
ser.close();
|
||||
}
|
||||
|
||||
bool BNO055Activity::start() {
|
||||
if(!isOpen() && !open()) return false;
|
||||
|
||||
ROS_INFO("starting");
|
||||
|
||||
if(!pub_data) pub_data = nh.advertise<sensor_msgs::Imu>("data", 1);
|
||||
if(!pub_raw) pub_raw = nh.advertise<sensor_msgs::Imu>("raw", 1);
|
||||
if(!pub_mag) pub_mag = nh.advertise<sensor_msgs::MagneticField>("mag", 1);
|
||||
if(!pub_temp) pub_temp = nh.advertise<sensor_msgs::Temperature>("temp", 1);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool BNO055Activity::spinOnce( ) {
|
||||
ros::Time time = ros::Time::now();
|
||||
uint64_t t = 1000 * (uint64_t)time.sec + (uint64_t)time.nsec / 1e6;
|
||||
|
||||
if(!ser.available()) {
|
||||
return false;
|
||||
}
|
||||
|
||||
int header_bytes = 0;
|
||||
imu_record record;
|
||||
|
||||
unsigned char c = 0;
|
||||
while(header_bytes < 4) {
|
||||
ser.read(&c, 1);
|
||||
if(c == 0xF0) header_bytes++;
|
||||
else header_bytes = 0;
|
||||
}
|
||||
|
||||
size_t bytes_read;
|
||||
|
||||
bytes_read = ser.read((uint8_t*)&record, 54);
|
||||
|
||||
ROS_DEBUG_STREAM("read " << bytes_read << " bytes");
|
||||
|
||||
if(bytes_read < 54) {
|
||||
return false;
|
||||
}
|
||||
|
||||
seq++;
|
||||
|
||||
sensor_msgs::Imu msg_raw;
|
||||
msg_raw.header.stamp = time;
|
||||
msg_raw.header.frame_id = frame_id;
|
||||
msg_raw.header.seq = seq;
|
||||
msg_raw.linear_acceleration.x = (double)record.raw_linear_acceleration_x / 100.0;
|
||||
msg_raw.linear_acceleration.y = (double)record.raw_linear_acceleration_y / 100.0;
|
||||
msg_raw.linear_acceleration.z = (double)record.raw_linear_acceleration_z / 100.0;
|
||||
msg_raw.angular_velocity.x = (double)record.raw_angular_velocity_x / 900.0;
|
||||
msg_raw.angular_velocity.y = (double)record.raw_angular_velocity_y / 900.0;
|
||||
msg_raw.angular_velocity.z = (double)record.raw_angular_velocity_z / 900.0;
|
||||
|
||||
sensor_msgs::MagneticField msg_mag;
|
||||
msg_mag.header.stamp = time;
|
||||
msg_mag.header.frame_id = frame_id;
|
||||
msg_mag.header.seq = seq;
|
||||
msg_mag.magnetic_field.x = (double)record.raw_magnetic_field_x / 16.0;
|
||||
msg_mag.magnetic_field.y = (double)record.raw_magnetic_field_y / 16.0;
|
||||
msg_mag.magnetic_field.z = (double)record.raw_magnetic_field_z / 16.0;
|
||||
|
||||
sensor_msgs::Imu msg_data;
|
||||
msg_data.header.stamp = time;
|
||||
msg_data.header.frame_id = frame_id;
|
||||
msg_data.header.seq = seq;
|
||||
msg_data.orientation.w = (double)record.fused_orientation_w;
|
||||
msg_data.orientation.x = (double)record.fused_orientation_x;
|
||||
msg_data.orientation.y = (double)record.fused_orientation_y;
|
||||
msg_data.orientation.z = (double)record.fused_orientation_z;
|
||||
msg_data.linear_acceleration.x = (double)record.fused_linear_acceleration_x / 100.0;
|
||||
msg_data.linear_acceleration.y = (double)record.fused_linear_acceleration_y / 100.0;
|
||||
msg_data.linear_acceleration.z = (double)record.fused_linear_acceleration_z / 100.0;
|
||||
msg_data.angular_velocity.x = (double)record.raw_angular_velocity_x / 900.0;
|
||||
msg_data.angular_velocity.y = (double)record.raw_angular_velocity_y / 900.0;
|
||||
msg_data.angular_velocity.z = (double)record.raw_angular_velocity_z / 900.0;
|
||||
|
||||
sensor_msgs::Temperature msg_temp;
|
||||
msg_temp.header.stamp = time;
|
||||
msg_temp.header.frame_id = frame_id;
|
||||
msg_temp.header.seq = seq;
|
||||
msg_temp.temperature = (double)record.temperature;
|
||||
|
||||
pub_data.publish(msg_data);
|
||||
pub_raw.publish(msg_raw);
|
||||
pub_mag.publish(msg_mag);
|
||||
pub_temp.publish(msg_temp);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void BNO055Activity::stop() {
|
||||
ROS_INFO("stopping");
|
||||
|
||||
if(pub_data) pub_data.shutdown();
|
||||
if(pub_raw) pub_raw.shutdown();
|
||||
if(pub_mag) pub_mag.shutdown();
|
||||
if(pub_temp) pub_temp.shutdown();
|
||||
|
||||
close();
|
||||
}
|
||||
|
||||
bool BNO055Activity::isOpen() const {
|
||||
return ser.isOpen();
|
||||
}
|
||||
|
||||
}
|
||||
|
|
@ -0,0 +1,57 @@
|
|||
#include <imu_bno055/BNO055Activity.hpp>
|
||||
|
||||
int main(int argc, char *argv[]) {
|
||||
ros::NodeHandle *nh = NULL;
|
||||
ros::NodeHandle *nh_priv = NULL;
|
||||
imu_bno055::BNO055Activity *activity = NULL;
|
||||
|
||||
ros::init(argc, argv, "imu_bno055_node");
|
||||
|
||||
nh = new ros::NodeHandle( );
|
||||
if(!nh) {
|
||||
ROS_FATAL("Failed to initialize NodeHandle");
|
||||
ros::shutdown( );
|
||||
return -1;
|
||||
}
|
||||
|
||||
nh_priv = new ros::NodeHandle("~");
|
||||
if( !nh_priv ) {
|
||||
ROS_FATAL("Failed to initialize private NodeHandle");
|
||||
delete nh;
|
||||
ros::shutdown( );
|
||||
return -2;
|
||||
}
|
||||
|
||||
activity = new imu_bno055::BNO055Activity(*nh, *nh_priv);
|
||||
if(!activity) {
|
||||
ROS_FATAL("Failed to initialize activity");
|
||||
delete nh_priv;
|
||||
delete nh;
|
||||
ros::shutdown();
|
||||
return -3;
|
||||
}
|
||||
|
||||
if(!activity->start()) {
|
||||
ROS_FATAL("Failed to start activity");
|
||||
delete activity;
|
||||
delete nh_priv;
|
||||
delete nh;
|
||||
ros::shutdown();
|
||||
return -4;
|
||||
}
|
||||
|
||||
ros::Rate rate(200);
|
||||
while(ros::ok()) {
|
||||
rate.sleep();
|
||||
ros::spinOnce();
|
||||
activity->spinOnce();
|
||||
}
|
||||
|
||||
activity->stop();
|
||||
|
||||
delete activity;
|
||||
delete nh_priv;
|
||||
delete nh;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
|
@ -0,0 +1,202 @@
|
|||
cmake_minimum_required(VERSION 3.0.2)
|
||||
project(turtlebot_description)
|
||||
|
||||
## 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)
|
||||
|
||||
## 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 exec_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 exec_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
|
||||
# )
|
||||
|
||||
## 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 # Or other packages containing 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 exec_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 turtlebot_description
|
||||
# CATKIN_DEPENDS other_catkin_pkg
|
||||
# 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}/turtlebot_description.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/turtlebot_description_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
|
||||
# catkin_install_python(PROGRAMS
|
||||
# scripts/my_python_script
|
||||
# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
|
||||
# )
|
||||
|
||||
## Mark executables for installation
|
||||
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html
|
||||
# install(TARGETS ${PROJECT_NAME}_node
|
||||
# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
|
||||
# )
|
||||
|
||||
## Mark libraries for installation
|
||||
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html
|
||||
# install(TARGETS ${PROJECT_NAME}
|
||||
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
|
||||
# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
|
||||
# RUNTIME DESTINATION ${CATKIN_GLOBAL_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_turtlebot_description.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)
|
||||
|
|
@ -0,0 +1,7 @@
|
|||
<launch>
|
||||
<arg name="model" default="$(find turtlebot_description)/urdf/turtlebot.urdf.xacro"/>
|
||||
<param name="robot_description" command="$(find xacro)/xacro $(arg model)"/>
|
||||
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher"/>
|
||||
<node pkg="joint_state_publisher_gui" type="joint_state_publisher_gui" name="joint_state_publisher_gui"/>
|
||||
<node pkg="rviz" type="rviz" name="rviz" args="-d $(find turtlebot_description)/rviz/display.rviz"/>
|
||||
</launch>
|
||||
|
|
@ -0,0 +1,21 @@
|
|||
<launch>
|
||||
<arg name="model" default="$(find turtlebot_description)/urdf/turtlebot.urdf.xacro"/>
|
||||
<arg name="world" default="$(find kubot_description)/worlds/ku_lab/ku_model.sdf"/>
|
||||
<!-- <arg name="world" default="empty_world"/> -->
|
||||
|
||||
<param name="robot_description" command="$(find xacro)/xacro '$(find turtlebot_description)/urdf/turtlebot.urdf.xacro'" />
|
||||
|
||||
<include file="$(find gazebo_ros)/launch/empty_world.launch">
|
||||
<arg name="world_name" value="$(arg world)"/>
|
||||
<arg name="paused" value="false"/>
|
||||
<arg name="use_sim_time" value="true"/>
|
||||
<arg name="gui" value="true"/>
|
||||
<arg name="recording" value="false"/>
|
||||
<arg name="debug" value="false"/>
|
||||
</include>
|
||||
|
||||
<node pkg="gazebo_ros" type="spawn_model" name="spawn_model"
|
||||
args="-unpause -urdf -model robot -param robot_description"
|
||||
output="screen" respawn="false"/>
|
||||
|
||||
</launch>
|
||||
Binary file not shown.
File diff suppressed because one or more lines are too long
Binary file not shown.
|
After Width: | Height: | Size: 64 KiB |
Binary file not shown.
File diff suppressed because one or more lines are too long
Binary file not shown.
|
After Width: | Height: | Size: 2.4 KiB |
Binary file not shown.
Binary file not shown.
|
|
@ -0,0 +1,59 @@
|
|||
<?xml version="1.0"?>
|
||||
<package format="2">
|
||||
<name>turtlebot_description</name>
|
||||
<version>0.0.0</version>
|
||||
<description>The turtlebot_description package</description>
|
||||
|
||||
<!-- One maintainer tag required, multiple allowed, one person per tag -->
|
||||
<!-- Example: -->
|
||||
<!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
|
||||
<maintainer email="hour@todo.todo">hour</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>TODO</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/turtlebot_description</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>
|
||||
|
||||
|
||||
<!-- The export tag contains other, unspecified, tags -->
|
||||
<export>
|
||||
<!-- Other tools can request additional information be placed here -->
|
||||
|
||||
</export>
|
||||
</package>
|
||||
|
|
@ -0,0 +1,213 @@
|
|||
Panels:
|
||||
- Class: rviz/Displays
|
||||
Help Height: 78
|
||||
Name: Displays
|
||||
Property Tree Widget:
|
||||
Expanded:
|
||||
- /Global Options1
|
||||
- /Status1
|
||||
- /RobotModel1
|
||||
- /TF1
|
||||
- /TF1/Frames1
|
||||
Splitter Ratio: 0.5264706015586853
|
||||
Tree Height: 439
|
||||
- Class: rviz/Selection
|
||||
Name: Selection
|
||||
- Class: rviz/Tool Properties
|
||||
Expanded:
|
||||
- /2D Pose Estimate1
|
||||
- /2D Nav Goal1
|
||||
- /Publish Point1
|
||||
Name: Tool Properties
|
||||
Splitter Ratio: 0.5886790156364441
|
||||
- Class: rviz/Views
|
||||
Expanded:
|
||||
- /Current View1
|
||||
Name: Views
|
||||
Splitter Ratio: 0.5
|
||||
- Class: rviz/Time
|
||||
Name: Time
|
||||
SyncMode: 0
|
||||
SyncSource: ""
|
||||
Preferences:
|
||||
PromptSaveOnExit: true
|
||||
Toolbars:
|
||||
toolButtonStyle: 2
|
||||
Visualization Manager:
|
||||
Class: ""
|
||||
Displays:
|
||||
- Alpha: 0.5
|
||||
Cell Size: 1
|
||||
Class: rviz/Grid
|
||||
Color: 160; 160; 164
|
||||
Enabled: true
|
||||
Line Style:
|
||||
Line Width: 0.029999999329447746
|
||||
Value: Lines
|
||||
Name: Grid
|
||||
Normal Cell Count: 0
|
||||
Offset:
|
||||
X: 0
|
||||
Y: 0
|
||||
Z: 0
|
||||
Plane: XY
|
||||
Plane Cell Count: 10
|
||||
Reference Frame: <Fixed Frame>
|
||||
Value: true
|
||||
- Alpha: 1
|
||||
Class: rviz/RobotModel
|
||||
Collision Enabled: false
|
||||
Enabled: true
|
||||
Links:
|
||||
All Links Enabled: true
|
||||
Expand Joint Details: false
|
||||
Expand Link Details: false
|
||||
Expand Tree: false
|
||||
Link Tree Style: Links in Alphabetic Order
|
||||
base_footprint:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
base_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
base_scan:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
caster_back:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
imu_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
wheel_left_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
wheel_right_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
Name: RobotModel
|
||||
Robot Description: robot_description
|
||||
TF Prefix: ""
|
||||
Update Interval: 0
|
||||
Value: true
|
||||
Visual Enabled: true
|
||||
- Class: rviz/TF
|
||||
Enabled: true
|
||||
Filter (blacklist): ""
|
||||
Filter (whitelist): ""
|
||||
Frame Timeout: 15
|
||||
Frames:
|
||||
All Enabled: true
|
||||
base_footprint:
|
||||
Value: true
|
||||
base_link:
|
||||
Value: true
|
||||
base_scan:
|
||||
Value: true
|
||||
caster_back:
|
||||
Value: true
|
||||
imu_link:
|
||||
Value: true
|
||||
wheel_left_link:
|
||||
Value: true
|
||||
wheel_right_link:
|
||||
Value: true
|
||||
Marker Alpha: 1
|
||||
Marker Scale: 1
|
||||
Name: TF
|
||||
Show Arrows: true
|
||||
Show Axes: true
|
||||
Show Names: true
|
||||
Tree:
|
||||
base_footprint:
|
||||
base_link:
|
||||
base_scan:
|
||||
{}
|
||||
caster_back:
|
||||
{}
|
||||
imu_link:
|
||||
{}
|
||||
wheel_left_link:
|
||||
{}
|
||||
wheel_right_link:
|
||||
{}
|
||||
Update Interval: 0
|
||||
Value: true
|
||||
Enabled: true
|
||||
Global Options:
|
||||
Background Color: 48; 48; 48
|
||||
Default Light: true
|
||||
Fixed Frame: base_footprint
|
||||
Frame Rate: 30
|
||||
Name: root
|
||||
Tools:
|
||||
- Class: rviz/Interact
|
||||
Hide Inactive Objects: true
|
||||
- Class: rviz/MoveCamera
|
||||
- Class: rviz/Select
|
||||
- Class: rviz/FocusCamera
|
||||
- Class: rviz/Measure
|
||||
- Class: rviz/SetInitialPose
|
||||
Theta std deviation: 0.2617993950843811
|
||||
Topic: /initialpose
|
||||
X std deviation: 0.5
|
||||
Y std deviation: 0.5
|
||||
- Class: rviz/SetGoal
|
||||
Topic: /move_base_simple/goal
|
||||
- Class: rviz/PublishPoint
|
||||
Single click: true
|
||||
Topic: /clicked_point
|
||||
Value: true
|
||||
Views:
|
||||
Current:
|
||||
Class: rviz/Orbit
|
||||
Distance: 1.249600887298584
|
||||
Enable Stereo Rendering:
|
||||
Stereo Eye Separation: 0.05999999865889549
|
||||
Stereo Focal Distance: 1
|
||||
Swap Stereo Eyes: false
|
||||
Value: false
|
||||
Field of View: 0.7853981852531433
|
||||
Focal Point:
|
||||
X: 0
|
||||
Y: 0
|
||||
Z: 0
|
||||
Focal Shape Fixed Size: false
|
||||
Focal Shape Size: 0.05000000074505806
|
||||
Invert Z Axis: false
|
||||
Name: Current View
|
||||
Near Clip Distance: 0.009999999776482582
|
||||
Pitch: 0.4003998637199402
|
||||
Target Frame: <Fixed Frame>
|
||||
Yaw: 4.389971733093262
|
||||
Saved: ~
|
||||
Window Geometry:
|
||||
Displays:
|
||||
collapsed: false
|
||||
Height: 736
|
||||
Hide Left Dock: false
|
||||
Hide Right Dock: false
|
||||
QMainWindow State: 000000ff00000000fd00000004000000000000015600000242fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d00000242000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000242fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d00000242000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b80000003efc0100000002fb0000000800540069006d00650100000000000004b8000003bc00fffffffb0000000800540069006d00650100000000000004500000000000000000000002470000024200000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
|
||||
Selection:
|
||||
collapsed: false
|
||||
Time:
|
||||
collapsed: false
|
||||
Tool Properties:
|
||||
collapsed: false
|
||||
Views:
|
||||
collapsed: false
|
||||
Width: 1208
|
||||
X: 72
|
||||
Y: 27
|
||||
|
|
@ -0,0 +1,180 @@
|
|||
<?xml version="1.0"?>
|
||||
|
||||
<robot name="turtlebot" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
<xacro:arg name="model" default="$(find turtlebot_description)/urdf/turtlebot.urdf.xacro"/>
|
||||
|
||||
<xacro:include filename="$(find turtlebot_description)/urdf/turtlebot_gazebo.xacro"/>
|
||||
|
||||
<link name = "base_footprint"/>
|
||||
|
||||
<link name="base_link">
|
||||
<visual>
|
||||
<origin xyz="-0.2 0.2 -0.07" rpy="1.5708 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://turtlebot_description/meshes/bases/kubot_base.STL" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
<material name="light_black"/>
|
||||
</visual>
|
||||
|
||||
<collision>
|
||||
<origin xyz="-0.064 0 0.047" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="0.266 0.266 0.094"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
<inertial>
|
||||
<origin xyz="0.0 0 0.0" rpy="0 0 0"/>
|
||||
<mass value="1.6329594e+00"/>
|
||||
<inertia ixx="8.7002718e-03" ixy="-4.7576583e-05" ixz="1.1160499e-04"
|
||||
iyy="8.6195418e-03" iyz="-3.5422299e-06"
|
||||
izz="1.4612727e-02"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<link name="wheel_left_link">
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="1.57 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://turtlebot_description/meshes/wheels/left_tire.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
<material name="dark"/>
|
||||
</visual>
|
||||
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.018" radius="0.033"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
<inertial>
|
||||
<origin xyz="0 0 0" />
|
||||
<mass value="2.8498940e-02" />
|
||||
<inertia ixx="1.1175580e-05" ixy="-4.2369783e-11" ixz="-5.9381719e-09"
|
||||
iyy="1.1192413e-05" iyz="-1.4400107e-11"
|
||||
izz="2.0712558e-05" />
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<link name="wheel_right_link">
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="1.57 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://turtlebot_description/meshes/wheels/right_tire.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
<material name="dark"/>
|
||||
</visual>
|
||||
|
||||
<collision>
|
||||
<origin xyz="0 0.001 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.018" radius="0.033"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
<inertial><launch>
|
||||
<arg name="model" default="$(find turtlebot_description)/urdf/turtlebot.urdf.xacro"/>
|
||||
<param name="robot_description" command="$(find xacro)/xacro --inorder $(arg model)"/>
|
||||
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher"/>
|
||||
<node pkg="joint_state_publisher_gui" type="joint_state_publisher_gui" name="joint_state_publisher_gui"/>
|
||||
<node pkg="rviz" type="rviz" args="-d $(find turtlebot_description)/rviz/display.rviz"/>
|
||||
</launch>
|
||||
|
||||
<origin xyz="0 0 0" />
|
||||
<mass value="2.8498940e-02" />
|
||||
<inertia ixx="1.1175580e-05" ixy="-4.2369783e-11" ixz="-5.9381719e-09"
|
||||
iyy="1.1192413e-05" iyz="-1.4400107e-11"
|
||||
izz="2.0712558e-05" />
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<link name="caster_back">
|
||||
|
||||
|
||||
<collision>
|
||||
<origin xyz="0 0.004 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="0.030 0.009 0.020"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
<inertial>
|
||||
<origin xyz="0 0 0" />
|
||||
<mass value="0.005" />
|
||||
<inertia ixx="0.001" ixy="0.0" ixz="0.0"
|
||||
iyy="0.001" iyz="0.0"
|
||||
izz="0.001" />
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<link name="imu_link"/>
|
||||
|
||||
<link name="base_scan">
|
||||
<visual>
|
||||
<origin xyz="0 0 0.0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://turtlebot_description/meshes/sensors/lds.stl" scale="0.001 0.001 0.001"/>
|
||||
</geometry>
|
||||
<material name="dark"/>
|
||||
</visual>
|
||||
|
||||
<collision>
|
||||
<origin xyz="0.015 0 -0.0065" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.0315" radius="0.045"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
<inertial>
|
||||
<mass value="0.114" />
|
||||
<origin xyz="0 0 0" />
|
||||
<inertia ixx="0.001" ixy="0.0" ixz="0.0"
|
||||
iyy="0.001" iyz="0.0"
|
||||
izz="0.001" />
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
|
||||
<joint name="base_joint" type="fixed">
|
||||
<parent link="base_footprint"/>
|
||||
<child link="base_link" />
|
||||
<origin xyz="0.1 0 -0.01" rpy="0 0 0"/>
|
||||
</joint>
|
||||
|
||||
<joint name="wheel_left_joint" type="continuous">
|
||||
<parent link="base_link"/>
|
||||
<child link="wheel_left_link"/>
|
||||
<origin xyz="0.0 0.144 0.023" rpy="-1.57 0 0"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
</joint>
|
||||
|
||||
<joint name="wheel_right_joint" type="continuous">
|
||||
<parent link="base_link"/>
|
||||
<child link="wheel_right_link"/>
|
||||
<origin xyz="0.0 -0.144 0.023" rpy="-1.57 0 0"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
</joint>
|
||||
|
||||
<joint name="caster_back" type="fixed">
|
||||
<parent link="base_link"/>
|
||||
<child link="caster_back"/>
|
||||
<origin xyz="-0.177 0 -0.004" rpy="-1.57 0 0"/>
|
||||
</joint>
|
||||
|
||||
|
||||
|
||||
<joint name="imu_joint" type="fixed">
|
||||
<parent link="base_link"/>
|
||||
<child link="imu_link"/>
|
||||
<origin xyz="0.0 0 0.068" rpy="0 0 0"/>
|
||||
</joint>
|
||||
|
||||
<joint name="scan_joint" type="fixed">
|
||||
<parent link="base_link"/>
|
||||
<child link="base_scan"/>
|
||||
<origin xyz="-0.024 0 0.122" rpy="0 0 0"/>
|
||||
</joint>
|
||||
|
||||
|
||||
</robot>
|
||||
|
|
@ -0,0 +1,85 @@
|
|||
<?xml version="1.0"?>
|
||||
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="turtlebot">
|
||||
|
||||
<gazebo reference="base_link">
|
||||
<material>Gazebo/DarkGrey</material>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="base_scan">
|
||||
<material>Gazebo/FlatBlack</material>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference ="wheel_left_link">
|
||||
<mu1>1000000</mu1>
|
||||
<mu2>1000000</mu2>
|
||||
<kp>500000</kp>
|
||||
<kd>10</kd>
|
||||
<minDepth>0.001</minDepth>
|
||||
<maxVel>0.1</maxVel>
|
||||
<fdir1>1 0 0</fdir1>
|
||||
<material>Gazebo/FlatBlack</material>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference ="wheel_right_link">
|
||||
<mu1>100000</mu1>
|
||||
<mu2>100000</mu2>
|
||||
<kp>500000</kp>
|
||||
<kd>10</kd>
|
||||
<minDepth>0.001</minDepth>
|
||||
<maxVel>0.1</maxVel>
|
||||
<fdir1>1 0 0</fdir1>
|
||||
<material>Gazebo/FlatBlack</material>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="caster_back_right_link">
|
||||
<mu1>0.1</mu1>
|
||||
<mu2>0.1</mu2>
|
||||
<kp>1000000</kp>
|
||||
<kd>100</kd>
|
||||
<minDepth>0.001</minDepth>
|
||||
<maxVel>1</maxVel>
|
||||
<fdir1>1 0 0</fdir1>
|
||||
<material>Gazebo/FlatBlack</material>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="caster_back_left_link">
|
||||
<mu1>0.1</mu1>
|
||||
<mu2>0.1</mu2>
|
||||
<kp>1000000</kp>
|
||||
<kd>100</kd>
|
||||
<minDepth>0.001</minDepth>
|
||||
<maxVel>1</maxVel>
|
||||
<fdir1>1 0 0</fdir1>
|
||||
<material>Gazebo/FlatBlack</material>
|
||||
</gazebo>
|
||||
|
||||
<gazebo>
|
||||
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
|
||||
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
|
||||
<lagacyModeNS>true</lagacyModeNS>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
|
||||
<transmission name="wheel_left_tranmission">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="wheel_left_joint">
|
||||
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="wheel_left_actuator">
|
||||
<mechanicalReduction>1.0</mechanicalReduction>
|
||||
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
|
||||
</actuator>
|
||||
</transmission>
|
||||
|
||||
<transmission name="wheel_right_tranmission">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="wheel_right_joint">
|
||||
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="wheel_right_actuator">
|
||||
<mechanicalReduction>1.0</mechanicalReduction>
|
||||
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
|
||||
</actuator>
|
||||
</transmission>
|
||||
</robot>
|
||||
Loading…
Reference in New Issue