Giter Site home page Giter Site logo

linorobot / linorobot Goto Github PK

View Code? Open in Web Editor NEW
956.0 60.0 346.0 11.78 MB

Autonomous ground robots (2WD, 4WD, Ackermann Steering, Mecanum Drive)

Home Page: http://linorobot.org

License: BSD 2-Clause "Simplified" License

C++ 96.53% CMake 0.10% Processing 0.86% C 2.50%
ros agv 2wd 4wd ackermann mecanum-wheel robotics autonomous-vehicles autonomous linorobot

linorobot's Introduction

linorobot Build Status

Linorobot is a suite of Open Source ROS compatible robots that aims to provide students, developers, and researchers a low-cost platform in creating new exciting applications on top of ROS.

You can also check out the ROS2 port of this project linorobot2.

Tutorial

You can read the full tutorial how to build your robot here.

Multiplatform

Supports multiple types of robot base:

  • 2WD
  • 4WD
  • Ackermann Steering
  • Mecanum drive

alt text

Works on:

  • ROS Indigo (Ubuntu 14.04)
  • ROS Kinetic (Ubuntu 16.04)

Hardware

Fabricate your own Teensy 3.1/3.2 shield,

alt textalt text

or wire it on your own. Wiring diagrams are also provided. alt text

Supported IMUs:

  • GY-85
  • MPU6050
  • MPU9150
  • MPU9250

The IMU drivers are based on i2cdevlib.

Supported Motor Drivers:

  • L298 (MAX: 35V, 2A)
  • BTS7960 (MAX: 24V, 43A)
  • Electronic Speed Controllers (ESC) w/ Reverse. This has been tested to control brushless motors used in RC cars and hoverboards.

Supported ROS Compatible Sensors:

  • XV11 Lidar
  • RPLidar
  • YDLIDAR X4
  • Hokuyo (SCIP 2.2 Compliant)
  • Intel RealSense R200
  • Kinect

Tested on Linux compatible ARM dev boards:

  • Raspberry Pi 3/B+
  • Jetson TK1
  • Jetson TX1
  • Odroid XU4
  • Radxa Rock Pro
    **Technically this should also work with any ARM dev board at least (1GB RAM) that runs Ubuntu Trusty or Xenial.

Installation

alt text

git clone https://github.com/linorobot/lino_install && cd lino_install
./install <base> <sensor>

Firmware

Flexible and configurable components. linorobot_ws/teensy/firmware/lib/config/lino_base_config.h

Robot base configuration:

//uncomment the base you're building
#define LINO_BASE DIFFERENTIAL_DRIVE
// #define LINO_BASE SKID_STEER
// #define LINO_BASE ACKERMANN
// #define LINO_BASE ACKERMANN1
// #define LINO_BASE MECANUM

IMU configuration:

//uncomment the IMU you're using
#define USE_GY85_IMU
// #define USE_MP6050_IMU
// #define USE_MPU9150_IMU
// #define USE_MPU9250_IMU

Motor driver configuration:

//uncomment the motor driver you're using
#define USE_L298_DRIVER
// #define USE_BTS7960_DRIVER
// #define USE_ESC

Motor configuration:

//define your robot' specs here
#define MAX_RPM 330               // motor's maximum RPM
#define COUNTS_PER_REV 1550       // wheel encoder's no of ticks per rev
#define WHEEL_DIAMETER 0.10       // wheel's diameter in meters
#define PWM_BITS 8                // PWM Resolution of the microcontroller
#define LR_WHEELS_DISTANCE 0.235  // distance between left and right wheels
#define FR_WHEELS_DISTANCE 0.30   // distance between front and rear wheels
#define MAX_STEERING_ANGLE 0.415  // max steering angle. This only applies to Ackermann steering

Uploading the codes:

cd ~/linorobot_ws/src/linorobot/teensy/firmware
platformio run --target upload

Creating a Map

alt text

Launch base driver:

roslaunch linorobot bringup.launch

Launch mapping packages:

roslaunch linorobot slam.launch

Autonomous Navigation

IMAGE ALT TEXT

Launch base driver:

roslaunch linorobot bringup.launch

Launch navigation packages:

roslaunch linorobot navigate.launch

linorobot's People

Contributors

blockbyblock avatar dominsch avatar grassjelly avatar jafarabdi avatar methyldragon avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

linorobot's Issues

MPU6050 Support

Any idea when MPU6050 support is going to be implemented?

Unable to let motors turn backward

It seems that one of the last patches has introduced an error into the Motor.cpp file. Currently (line 16 & 17) sets "pinMode(motor_pinA_, OUTPUT);" twice. This hinders motor_pinB to be set correctly, which in turn prohibits backward driving. It should be (as it was in earlier versions) :

        pinMode(motor_pinA_, OUTPUT);
        pinMode(motor_pinB_, OUTPUT);

Cheers,

Chris

The tangential velocity for 2wd is doubled

I have a 2WD platform on the caterpillar tracks. Angular velocity shows 2 times more.
It is possible that the radius is incorrectly specified when calculating the tangential velocity.

Possible without encoders???

Hello, can anyone suggest me if it is possible to run this robot without wheel encoders? We are using high torque gear motors and it's very difficult to place external encoders on wheels. Can't it calculate the value from the imu data only? If so what's the proccedure ?
Also, built in encoders are not availbale for the kind of motors that we are using. Any kind of suggestion is appreciated. TIA.

pid to pwm

Hi
I caught my attention while browsing through scripts. You input rpm type value in pid and send the output value directly to the motor as pwm. how did covert this? I didn't understand.

Compile Problems - Teensy 3.5/3.6

When trying to compile and flash the Teensy firmware a number of errors pop-up when using Teensy 3.5 or 3.6 as target platforms. The reason is that the file "direct_pin_read.h", located in ... /src/linorobot/teensy/firmware/lib/encoder/utility only addresses Teensy 3.1 and 3.2 platforms. An easy fix is to replace line 4 by

#if defined(AVR) || defined(MK20DX128) || defined(MK20DX256) || defined(MK64FX512) || defined(MK66FX1M0)

Cheers

Chris

Ros 2 migration

Any plan for ROS 2 Migration

I guess it’s not too complicated, pls correct me

Thanks

Motor's rpm and pwm value

The rpm range is 0-330, but the PWM range is 0-255. Is that right? why?

motor1_controller.spin(motor1_pid.compute(req_rpm.motor1, current_rpm1));
Controller::spin
analogWrite(pwm_pin_, abs(pwm));

Hello,encoder problem

hi,I have a question for a long time.Now i want to make a car with the mecanum wheel,and I have Arduino Mega2560,motor dirver...,enen,I cheak the Mega2560 have 6 pins for interrupts(2,3,18,19,20,21 pins).But we have 4 wheels,and can we use analog pin for the interrupts to count the encoders.pelase forgive my poor English,Looking forward to your reply!

Move robot multi point

Hi. Thanks for your tutorial.
I want multiple point on map and repeat this points.
I don't know how can do that?
Can you help me? Thanks you.

Angular velocity bug

For 2WD platform, when calculating the angular velocity is half of the actual value.
In the kinematics file, the getvel function is calculated incorrectly, the code is as follows:
vel.angular_z = (average_rps_a * wheel_circumference_) / ((wheels_x_distance_ / 2) + (wheels_y_distance_ / 2));
Here, 4WD and 2WD are calculated separately.

Pinout for the xv11?

Is there a pinout on where and how to attach the xv11 lidar? (jetson tx1) Is it connected to the teensy or the jetson gpio?

Also is there an easy way to configure both an xv11 and a kinect to work together?

Thank you, this is an amazing project!

  • Adrian

ROS melodic lino_udev not found

hi
please help
i already follow the instruction to use Lino robot with ROS melodic
when i type roslaunc lino_udev lino_udev.py
then lino_udev not found

thanks

Ackermann with 4ED

Hi,

is it possible to configure it for a 4 wheel drive with Ackermann steering on front wheels?

if not - what is the best "workaround" - switch off rear wheels motors when steering?

E: Unable to locate package python-gudev

I am installing on Ubuntu 20.04. I've successfully installed ROS noetic. When attempting:

./install 2wd ydlidar
I see this:

INSTALLING NOW....

Hit:1 http://ports.ubuntu.com/ubuntu-ports focal InRelease
Hit:2 http://packages.ros.org/ros/ubuntu focal InRelease
Hit:3 http://ports.ubuntu.com/ubuntu-ports focal-updates InRelease
Hit:4 http://ports.ubuntu.com/ubuntu-ports focal-backports InRelease
Hit:5 http://ports.ubuntu.com/ubuntu-ports focal-security InRelease
Reading package lists... Done
Reading package lists... Done
Building dependency tree
Reading state information... Done
Note, selecting 'python-dev-is-python2' instead of 'python-dev'
E: Unable to locate package python-gudev

I know that I am not the only one to see this but lots of googling hasn't solved it for me yet. So I have some questions:

  1. Does the Linorobot software package depend on/support just python2, or python3, or either one?
  2. Is there a known incompatibility with Ubuntu 20.04?
  3. Is there a known incompatibility with ROS Noetic?

Thanks

Strange thing with Arduino MEGA

Dear All,

When porting teensy firmware to Arduino MEGA, there is some magic bug happens.
I do not know why, but after PID controller compute function it can send 257 value to PWM when it goes to backward.

I fix it by hardcoding this dynamic PWM_MAX value in config file by 255 and -255 in PWM_MAX and PWM_MIN.

I have changed firmware to make it okay with Arduino Mega. May I push it to linorobot, so anybody can use it?

Big wheel low RPM speed calculation problem

Hi

I have a robot rotating at a max of 25 RPM with 250 mm wheels. The encoders are are directly on the wheel shaft and have a low resolution of 20 tick per turns.

I am at the very beginning of my pre-operational testing. The speed loop behavior is strange.

The calculated linear velocity at start around is 1.75 m/s ( when the max speed for a 0.25 m wheel at 25 rpm is 0.33 m/s ) ???

The control loop make the wheel jog forward and backward around the starting position ???

Previously i used the same mostly the same setup with a smaller robot but at that time i had a encoder with 900 tick per turn with a motor rotating at 220 rpm with 0.06m wheels and every thing was running perfectly)

With the motor that i have it is difficult (if not imposible to have the encoder on the motor shaft )

On my car, when the speed is set to be less than 0.0157m/s, the car does not respond.

I am not a native English speaker,Please forgive my poor English.
Hello, thank you very much for providing such excellent software. I have successfully run your firmware on my own robot, but I found a little problem in my test. I am not sure if it is a bug, here Ask your advice:
My robot is a two-wheeled differential steering tracked vehicle with a wheel diameter of 0.3m. In my test, I found that no matter how I adjust the parameters in lino_base_config.h, I cannot set the minimum linear speed of my car to less than 0.0157 m/ s, after reading the firmware of the lower computer carefully, I found that the getRPM function for calculating the speed in the encode encoder library file returns int type data, and the data returned by the getRPM function in the kinematics library is also int type. During adjustment, if you want the car to move at less than 0.0157m/s, the speed calculated by kinematics.getRPM will be less than 1r/min, and because the int type data is returned, the rpm less than 1r/min will default to 0. The subsequent PID adjustment process will not work. At present, I have changed the data type in the kinematics, encode and other codes to change the problem, and my car can run at a speed less than 0.01m/s.
Please forgive my poor English.

Couldn't find linobase

Hello
I'm quite new in ROS and having problem with the tutorial I follow in linorobot and cannot find any issues like this

I have follow all the order from the wiki but I cannot continue for calibrating the IMU.
i have succed run the UDEV rules from #31.
when i use
$ ls/ dev/ linobase
it appears with a green word

after uploading firmware and run roslaunch minimal launch
$ roscd linorobot/teensy/firmware
$ platformio run --target upload
$ roslaunch linorobot minimal.launch

The error appears like :
[ERROR] [1596438890.774381]: Error opening serial: [Errno 2] could not open port /dev/linobase: [Errno 2] No such file or directory: '/dev/linobase'

Anyone has dealing this too?
I have checked that after i upload the firmware, the teensy i use (i dont know how) suddenly changed the port to dev/bus/usb/003/050 Bootloader

the system I use are :
Teensy 4.0
Melodic

NB : I have setting the platformIO for the teensy 4.0 from here https://github.com/ros-drivers/rosserial/pull/456/files

Thank you
Best regards

The ESC can not work well because the pid error too large

I have a Rc car , but when i make my teensy Output pwm wave ,my esc can not work, my motor is not runing. Then i find the reason of it that is the pid error too large!!

so I add blow code to make the pid error is not too large ! (PID.cpp)

double PID::compute(float setpoint, float measured_value)
{
    double error;
    double pid;

    //setpoint is constrained between min and max to prevent pid from having too much error
    error = setpoint - measured_value;

    if (error > 0)
    {
        if (error >= max_error)
        {
            error = max_error;
        }
    }else{
        if (error <= -max_error)
        {
            error = -max_error;
        }

    }

    integral_ += error;
    derivative_ = error - prev_error_;

    if(setpoint == 0 && error == 0)
    {
        integral_ = 0;
    }

    pid = (kp_ * error) + (ki_ * integral_) + (kd_ * derivative_);
    prev_error_ = error;

    return constrain(pid, min_val_, max_val_);
}

Wheels

Hi there, do you still do ROS? I am building a similar robot and I am stuck on 1 thing which I would absolutely love help with.

I am using Hector Slam which produces /odom etc for my lidar. I have a URDF. How do I link the wheel in the mode (mine is lwheel, yours is wheel_left) to the system as it always shows as an error in RVIZ?

ydlidar package is out of date

At least from my personal experience. The version of the ydlidar package that is included in the linorobot is out of date and doesn't work correctly. I was able to solve my problem my using the current package: https://github.com/YDLIDAR/ydlidar_ros. It is called ydlidar-ros while linorobot refers to it as just ydlidar so some renaming was necessary as well.

Jetson nano

hi...

Can i use jetson nano for arm dev board

thanks
rizki

Platformio requires python 3.6 or newer

This issue is difficult. To install the Teensy code requires ROS routines (which use Python 2.7) but Platformio won't work with that old version. I made a custom version of Ubuntu 18.04 on a micro SD card (for my Raspberry Pi 4) and removed Python 2.7 (which removed most of ROS Melodic) and then Platformio installed well. But to compile and transfer code to Teensy, it requires many ROS items for the code! I don't find a simple answer.

PID calibration for 4wd

Hi,

I have finished making a heavy 4wd robot following the guide. The robot currently weighs over 20 kgs with 10 inch wheels. The build and installation of the code went flawless, no problems whatsoever and I thank you for this great opensource code. I am however clueless as to how to configure the PID values. The robot can run straight forward and backward but not able to turn at its place. I am not sure how should I start determining the best value for k_p, k_d and k_i. I also followed the guide that you have included but it was not helpful. Would be happy to get some feedback. Thanks

Mecanum robot Y velocity issue

The robot should move left when given positive Y velocity but instead it moves right and also other way around. Why velocity in Y is reversed.

lino_msgs i can not use lino_msgs in cpp

ros error lino_msgs/Imu.h: No such file or directory
compilation terminated.
ros doesn't know lino_msgs header file
but Arduino ok.
Cmakelist, where i have to add library lino_msgs header file .
thy.

Is it possible to connect the teensy via I2C?

There is no documentation on how to connect the teensy to the basecontroller computer, so I assume the usual way is via USB.

Is it possible to connect the teensy via I2C with a raspberry?

/teensy code running directly on RPi3 with no Teensy module

Hi, amazing work here.

Quick question, how can I run the /teensy/firmware code directly on a Raspberry Pi 3 with no Teensy module? Is there a port or method without modifiying so many files? I have both the IMU and servo/ESC controller attached to the I2C link directly on the board configured with ROS and Ubuntu.

My setup: ODROID XU4 with Shifter Shield for 3.3V pins, which makes the connectivity similar to RPi3. I have Realsense D435 camera, MPU6050 IMU, PCA9685 ESC/servo controller. All working together with RTABmap and custom ESC controller (documentation will be put online soon).

Thanks!

Scanse Sweep compatibility

Hi,

I'm using linorobot with Jetson Nano (Ubuntu 18.04), Arduino Mega and Sweep Lidar.
I configured the linobase module and the minimal.launch is working fine.

In order to be able to use Sweep Lidar I added it's package into the linorobot directory and catkin_make it. After that, I changed the linorobot launch files to run the sweep lidar launch file.
When I launch the bringup.launch file, I receive those error.

My question is: What else would need to be done in order to use the Sweep Lidar?

started roslaunch server http://192.168.43.50:34635/

SUMMARY
========

PARAMETERS
 * /apply_calib/calib_file: /home/jetson/lino...
 * /apply_calib/calibrate_gyros: True
 * /ekf_localization/base_link_frame: base_footprint
 * /ekf_localization/diagnostics_agg: True
 * /ekf_localization/frequency: 50
 * /ekf_localization/imu0: /imu/data
 * /ekf_localization/imu0_config: [False, False, Fa...
 * /ekf_localization/imu0_differential: True
 * /ekf_localization/imu0_relative: True
 * /ekf_localization/odom0: /raw_odom
 * /ekf_localization/odom0_config: [False, False, Fa...
 * /ekf_localization/odom0_differential: True
 * /ekf_localization/odom0_relative: False
 * /ekf_localization/odom_frame: odom
 * /ekf_localization/two_d_mode: True
 * /ekf_localization/world_frame: odom
 * /imu_filter_madgwick/fixed_frame: base_footprint
 * /imu_filter_madgwick/orientation_stddev: 0.05
 * /imu_filter_madgwick/publish_tf: False
 * /imu_filter_madgwick/use_mag: True
 * /imu_filter_madgwick/use_magnetic_field_msg: True
 * /imu_filter_madgwick/world_frame: enu
 * /pointcloud_to_laserscan/angle_increment: 0.0174533
 * /pointcloud_to_laserscan/angle_max: 3.14
 * /pointcloud_to_laserscan/angle_min: -3.14
 * /pointcloud_to_laserscan/concurrency_level: 1
 * /pointcloud_to_laserscan/max_height: 1.0
 * /pointcloud_to_laserscan/min_height: -1.0
 * /pointcloud_to_laserscan/range_max: 40.0
 * /pointcloud_to_laserscan/range_min: 0.0
 * /pointcloud_to_laserscan/scan_time: 0.1
 * /pointcloud_to_laserscan/target_frame: laser
 * /pointcloud_to_laserscan/transform_tolerance: 0.001
 * /pointcloud_to_laserscan/use_inf: True
 * /rosdistro: melodic
 * /rosserial_lino/baud: 57600
 * /rosserial_lino/port: /dev/linobase
 * /rosversion: 1.14.5
 * /sweep_node/frame_id: laser
 * /sweep_node/serial_baudrate: 115200
 * /sweep_node/serial_port: /dev/linolidar

NODES
  /
    apply_calib (imu_calib/apply_calib)
    base_footprint_to_base_link (tf2_ros/static_transform_publisher)
    base_footprint_to_imu_link (tf2_ros/static_transform_publisher)
    base_link_to_laser (tf2_ros/static_transform_publisher)
    ekf_localization (robot_localization/ekf_localization_node)
    imu_filter_madgwick (imu_filter_madgwick/imu_filter_node)
    lino_base_node (linorobot/lino_base_node)
    pointcloud_to_laserscan (pointcloud_to_laserscan/pointcloud_to_laserscan_node)
    rosserial_lino (rosserial_python/serial_node.py)
    sweep_node (sweep_ros/sweep_node)

auto-starting new master
process[master]: started with pid [26933]
ROS_MASTER_URI=http://192.168.43.50:11311

setting /run_id to 11079158-8627-11ea-ad52-12ed0dd4ce4d
process[rosout-1]: started with pid [26944]
started core service [/rosout]
process[rosserial_lino-2]: started with pid [26951]
process[apply_calib-3]: started with pid [26952]
process[imu_filter_madgwick-4]: started with pid [26953]
process[base_footprint_to_imu_link-5]: started with pid [26954]
[ INFO] [1587731298.663476387]: Starting ImuFilter
[ INFO] [1587731298.677961559]: Using dt computed from message headers
[ INFO] [1587731298.724266254]: Imu filter gain set to 0.100000
[ INFO] [1587731298.724941426]: Gyro drift bias set to 0.000000
[ INFO] [1587731298.725399145]: Magnetometer bias values: 0.000000 0.000000 0.000000
process[lino_base_node-6]: started with pid [26965]
process[base_footprint_to_base_link-7]: started with pid [26971]
process[ekf_localization-8]: started with pid [26972]
process[sweep_node-9]: started with pid [26983]
process[pointcloud_to_laserscan-10]: started with pid [26985]
process[base_link_to_laser-11]: started with pid [26987]
[ WARN] [1587731299.346980673]: Both imu0_differential and imu0_relative were set to true. Using differential mode.
[INFO] [1587731300.024167]: ROS Serial Python Node
[INFO] [1587731300.042407]: Connecting to /dev/linobase at 57600 baud
[INFO] [1587731302.160059]: Requesting topics...
Error: invalid response header checksum
[INFO] [1587731302.361959]: Note: publish buffer size is 512 bytes
[INFO] [1587731302.367370]: Setup publisher on raw_imu [lino_msgs/Imu]
[INFO] [1587731302.380240]: Note: subscribe buffer size is 512 bytes
[INFO] [1587731302.384288]: Setup subscriber on pid [lino_msgs/PID]
[INFO] [1587731302.396869]: Setup subscriber on cmd_vel [geometry_msgs/Twist]
[INFO] [1587731302.403159]: LINOBASE CONNECTED
[ERROR] [1587731302.409229]: Tried to publish before configured, topic id 125
[INFO] [1587731302.413351]: Requesting topics...
[ERROR] [1587731302.429750]: Tried to publish before configured, topic id 125
[INFO] [1587731302.433974]: Requesting topics...
[sweep_node-9] process has finished cleanly
log file: /home/jetson/.ros/log/11079158-8627-11ea-ad52-12ed0dd4ce4d/sweep_node-9*.log
[INFO] [1587731302.457929]: Setup publisher on raw_imu [lino_msgs/Imu]
[ERROR] [1587731302.488946]: Tried to publish before configured, topic id 125
[INFO] [1587731302.493745]: Requesting topics...
[INFO] [1587731302.538571]: Setup publisher on raw_vel [lino_msgs/Velocities]
[INFO] [1587731302.549725]: Setup publisher on raw_imu [lino_msgs/Imu]
[INFO] [1587731302.622646]: Setup publisher on raw_vel [lino_msgs/Velocities]
[INFO] [1587731302.638786]: Setup publisher on raw_imu [lino_msgs/Imu]
[ INFO] [1587731302.693795733]: Calibrating gyros; do not move the IMU
[ WARN] [1587731308.828438073]: Still waiting for data on topics /imu/data_raw and /imu/mag...
[ INFO] [1587731310.355790401]: Gyro calibration complete! (bias = [-0.056, 0.037, -0.012])
[ INFO] [1587731310.508411130]: First pair of IMU and magnetometer messages received.

Status of this project?

Hi @grassjelly -- what a wonderful project this is. I am having a great time with it. I was wondering whether it is still actively maintained or whether you have moved to other things. It would help me understand whether I want to build my stuff around it. Thanks!

firmware not finding lino_msgs/Velocities.h

Hi,
I have this error /home/michael/catkin_ws/src/linorobot/teensy/firmware/src/firmware/firmware.ino:12:34: fatal error: lino_msgs/Velocities.h: No such file or directory

I've cloned the package lino_msgs into my catkin workspace and was able to successfully to catkin_make with no errors.

Let me know if you have any clues as to what I might have missed.
Thank you,
Michael

Use of integers with getRPM causes issues with robots with large wheels.

The robot I built uses a 10-inch wheel (with a 12-inch wheel base) and I was having problems with getting the robot to achieve an accurate orientation. With a goal tolerance of 5 degrees, I was getting about +/-10 degrees. While digging into the problem, I discovered that because of the size of the wheel, the RPM required to home in on an orientation of about less than 5 degrees would require an RPM of less than 1. But because getRPM() in encoder.h returns an integer, a 0.999 RPM gets converted to 0 and the motors stop turning, even though the controller is still receiving twist commands. I changed the code to return a float and it seemed to solve my issue. Is there any reason it needs to be an integer?

Doubt about /tf

Hi @grassjelly,

I write you because I have a doubt about your robots.
In what part do you define the relation between the base_frame with the laser_frame?
How to publish the tf topic and the transformation?

Maybe the question are a bit basic.

Many thanks in advance.

Juan Antonio

Kinematic

What is the x_rpm_ , y_rpm_ and tan_rpm_ in kinematic library? And how calculate motors RPM from these parameters?

from 2WD to 4WD

I have installed linorobot by 2WD kinect. It works perfect.
Now trying to move to 4WD Mecanum lidar.

How to do that without reinstall ?

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.