All Projects → merose → Diff_drive

merose / Diff_drive

Licence: bsd-3-clause
ROS nodes for controlling and monitoring a differential drive robot.

Programming Languages

python
139335 projects - #7 most used programming language

Projects that are alternatives of or similar to Diff drive

Quickmcl
QuickMCL - Monte Carlo localisation for ROS
Stars: ✭ 24 (-68.83%)
Mutual labels:  robotics, ros
Pendulum
ROS, ROS2, real-time, control, pendulum
Stars: ✭ 37 (-51.95%)
Mutual labels:  robotics, ros
Joctomap
Java/Android wrapper for Octomap: an octree-based mapping library
Stars: ✭ 11 (-85.71%)
Mutual labels:  robotics, ros
Fourth robot pkg
4号機(KIT-C4)用リポジトリ
Stars: ✭ 7 (-90.91%)
Mutual labels:  robotics, ros
Icse Seip 2020 Replication Package
Replication package of the paper titled "How do you Architect your Robots? State of the Practice and Guidelines for ROS-based Systems" published at ICSE-SEIP 2020
Stars: ✭ 68 (-11.69%)
Mutual labels:  robotics, ros
Pepper plymouth ros
A set of launch files and configuration files for Plymouth University's Pepper robot
Stars: ✭ 22 (-71.43%)
Mutual labels:  robotics, ros
Navigator
NaviGator ASV on-board software
Stars: ✭ 29 (-62.34%)
Mutual labels:  robotics, ros
Gibsonenv
Gibson Environments: Real-World Perception for Embodied Agents
Stars: ✭ 666 (+764.94%)
Mutual labels:  robotics, ros
Vector ros
ROS package for Anki Vector home robot
Stars: ✭ 55 (-28.57%)
Mutual labels:  robotics, ros
Plankton
Open source simulator for maritime robotics researchers
Stars: ✭ 51 (-33.77%)
Mutual labels:  robotics, ros
Ros best practices
Best practices, conventions, and tricks for ROS. Do you want to become a robotics master? Then consider graduating or working at the Robotics Systems Lab at ETH in Zürich!
Stars: ✭ 799 (+937.66%)
Mutual labels:  robotics, ros
Hrim
An information model for robot hardware. Facilitates interoperability across modules from different robot manufacturers. Built around ROS 2.0
Stars: ✭ 61 (-20.78%)
Mutual labels:  robotics, ros
Behaviortree.cpp
Behavior Trees Library in C++. Batteries included.
Stars: ✭ 793 (+929.87%)
Mutual labels:  robotics, ros
Champ setup assistant
CHAMP Package Config Generator
Stars: ✭ 24 (-68.83%)
Mutual labels:  robotics, ros
Ardupilot
ArduPlane, ArduCopter, ArduRover, ArduSub source
Stars: ✭ 6,637 (+8519.48%)
Mutual labels:  robotics, ros
Ros Academy For Beginners
中国大学MOOC《机器人操作系统入门》代码示例 ROS tutorial
Stars: ✭ 861 (+1018.18%)
Mutual labels:  robotics, ros
Autorally
Software for the AutoRally platform
Stars: ✭ 595 (+672.73%)
Mutual labels:  robotics, ros
Linorobot
Autonomous ground robots (2WD, 4WD, Ackermann Steering, Mecanum Drive)
Stars: ✭ 598 (+676.62%)
Mutual labels:  robotics, ros
Openre
HandsFree OpenRE Tutorial
Stars: ✭ 41 (-46.75%)
Mutual labels:  robotics, ros
Ros2 java
Java and Android bindings for ROS2
Stars: ✭ 60 (-22.08%)
Mutual labels:  robotics, ros

= diff_drive -- Differential-Drive Controller :imagesdir: ./images

This package implements ROS nodes to control and monitor a differential-drive robot.

The package is intended as a lighter-weight solution than the ROS controller framework, albeit with lower performance since it is written in Python. If you need tight, real-time control, you may want to look at link:http://wiki.ros.org/ros_controllers[ros_controllers], a C++ package which includes a differential-drive controller that is integrated with link:http://wiki.ros.org/ros_control[ros_control] and link:http://wiki.ros.org/controller_manager[controller_manager]. Those controllers are designed to integrate with hardware in the same process, rather than using topics. Instead, this package expects to publish the desired motor speeds using standard ROS messages.

== Supplied Nodes

  • diff_drive_controller -- Converts from twist to wheel velocities for motors.
  • diff_drive_odometry -- Publishes odometry from wheel encoder data.
  • diff_drive_go_to_goal -- Moves the robot to a goal position.
  • diff_drive_mock_robot -- Implements a mock differential drive robot, for testing.

The nodes in this package are designed with these considerations:

  • The node and hardware implementing differential drive should deal only in encoder ticks.
  • Conversions to and from physical coordinates should happen within the nodes in this package.
  • This package should integrate cleanly with the navigation stack, perhaps with remappings.
  • Nodes should use standard topic and parameter names used by the navigation stack, but should allow remapping.

== Demo

To see all the nodes in this package in action, you can launch a demo from ROS. There are no dependencies other than the standard ROS packages.

 roslaunch diff_drive demo.launch

This launches rviz as part of the demo, and shows the robot position as a small coordinate system on a 0.25m grid. In rviz you can move the robot by clicking the 2D Nav Goal button in the tools panel at the top. Then click and drag within the grid to set the robot goal position and heading. The mock robot will move to that new pose, which you can see by the movement of the robot axes.

In the demo, both forward and backward movement is allowed, so if the goal position is behind the robot, it will move backward. You can force the robot to move foward only by setting the parameter ~forwardMovementOnly to true.

== ROS API

=== 1. diff_drive_controller

Listens for desired linear and angular velocity, and publishes corresponding wheel velocities, in encoder ticks per second, required to achieve those velocities.

==== Published Topics

~lwheel_desired_rate (std_msgs/Int32):: Desired left wheel rotation rate, in encoder ticks per second.

~rwheel_desired_rate (std_msgs/Int32):: Desired right wheel rotation rate, in encoder ticks per second.

==== Subscribed Topics

~cmd_vel (geometry_msgs/Twist):: Desired linear and angular velocity.

==== Parameters

~ticks_per_meter (double):: Number of encoder ticks per meter of travel.

~wheel_separation (double):: Distance between the two wheels (meters).

~rate (int, default: 50):: The rate that the output velocity target messages will be published (Hz).

~timeout (int, default: 0.2):: The maximum number of seconds expected between cmd_vel messages. If cmd_vel is not received before this limit, the controller will assume the commanding node has died and will set the desired wheel rates to zero, to stop the robot.

=== 2. diff_drive_odometry

Listens for wheel movement and rates and publishes the transform between the odom frame and the robot frame.

==== Published Topics

~odom -- (nav_msgs/Odometry):: The robot odometry -- the current robot pose.

~tf:: The transform between the odometry frame and the robot frame.

==== Subscribed Topics

~lwheel_ticks (std_msgs/Int32):: Cumulative encoder ticks of the left wheel.

~rwheel_ticks (std_msgs/Int32):: Cumulative encoder ticks of the right wheel.

~lwheel_rate (std_msgs/Float32):: Left wheel rotation rate, in encoder ticks per second.

~rwheel_rate (std_msgs/Float32):: Right wheel rotation rate, in encoder ticks per second.

==== Parameters

~ticks_per_meter (double):: Number of encoder ticks per meter of travel.

~wheel_separation (double):: Distance between the two wheels (m).

~rate (double, default 10.0):: The rate at which the tf and odom topics are published (Hz).

~timeout (double, default 0.2):: The amount of time to continue publishing desired wheel rates after receiving a twist message (seconds). If set to zero, wheel velocities will be sent only when a new twist message is received.

~base_frame_id (string, default: "base_link"):: The name of the base frame of the robot.

~odom_frame_id (string, default: "odom"):: The name of the odometry reference frame.

~encoder_min (int, default: -32768)::

~encoder_max (int, default: 32768):: The min and max value the encoder should output. Used to calculate odometry when the values wrap around.

~wheel_low_wrap (int, default: 0.3 * (encoder_max - encoder_min + 1) + encoder_min)::

~wheel_high_wrap (int, default: 0.7 * (encoder_max - encoder_min + 1) + encoder_min):: If a reading is greater than wheel_high_wrap and the next reading is less than wheel_low_wrap, then the reading has wrapped around in the positive direction, and the odometry will be calculated appropriately. The same concept applies for the negative direction.

=== 3. diff_drive_go_to_goal

Listens for new goal poses and computes velocities needed to achieve the goal.

==== Published Topics

~distance_to_goal (std_msgs/Float32):: Distance to the goal position (meters).

~cmd_vel (geometry_msgs/Twist):: Desired linear and angular velocity to move toward the goal pose.

==== Subscribed Topics

~goal (geometry_msgs/Pose):: Desired goal pose.

==== Parameters

~rate (float, default: 10):: Rate at which to publish desired velocities (Hz).

~goal_linear_tolerance (float, default: 0.1):: The distance from the goal at which the robot is assumed to have accomplished the goal position (meters).

~goal_angular_tolerance (float, default: 0.087):: The difference between robot angle and goal pose angle at which the robot is assumed to have accomplished the goal attitude (radians). Default value is approximately 5 degrees.

~max_linear_velocity (float, default: 0.2):: The maximum linear velocity toward the goal (meters/second).

~max_angular_velocity (float, default: 1.5):: The maximum angular velocity (radians/second).

~max_linear_acceleration (float, default: 4.0):: The maximum linear acceleration (meters/second^2).

~forwardMovementOnly (boolean, default: true):: If true, only forward movement is allowed to achieve the goal position. If false, the robot will move backward to the goal if that is the most direct path.

~Kp (float, default: 3.0):: Linear distance proportionality constant. Higher values make the robot accelerate more quickly toward the goal and decelerate less quickly.

~Ka (float: default: 8.0):: Proportionality constant for angle to goal position. Higher values make the robot turn more quickly toward the goal.

~Kb (float: default: -1.5):: Proportionality constant for angle to goal pose direction. Higher values make the robot turn more quickly toward the goal pose direction. This value should be negative, per Autonomous Mobile Robots.

The control law for determining the linear and angular velocity to move toward the goal works as follows. Let d be the distance to the goal. Let a be the angle between the robot heading and the goal position, where left is positive. Let b be the angle between the goal direction and the final pose angle, where left is positive. Then the robot linear and angular velocities are calculated like this:

v = Kp * d
w = Ka*a + Kb*b

See Autonomous Mobile Robots, Second Edition by Siegwart et. al., section 3.6.2.4. In this code, when the robot is near enough to the goal, v is set to zero, and w is simply Kb*b.

To ensure convergence toward the goal, Kp and Ka must be positive, Kb must be negative, and Ka must be greater than Kp. To ensure robust convergence, so that the robot never changes direction, Ka - 5/3*Kb - 2/pi*Kp must be greater than zero.

=== 4. diff_drive_mock_robot

Implements a simulation of perfect differential drive robot hardware. It immediately follows any speed commands received with infinite acceleration, and publishes the wheel encoder values and encoder rates.

==== Published Topics

~lwheel_ticks (std_msgs/Int32):: Cumulative encoder ticks of the left wheel.

~rwheel_ticks (std_msgs/Int32):: Cumulative encoder ticks of the right wheel.

~lwheel_rate (std_msgs/Float32):: Left wheel rotation rate, in encoder ticks per second.

~rwheel_rate (std_msgs/Float32):: Right wheel rotation rate, in encoder ticks per second.

==== Subscribed Topics

~lwheel_desired_rate (std_msgs/Int32):: Desired left wheel rotation rate, in encoder ticks per second.

~rwheel_desired_rate (std_msgs/Int32):: Desired right wheel rotation rate, in encoder ticks per second.

==== Parameters

~cmd_timeout (float, default: 0.2):: The amount of time after the last wheel rate message when the robot should stop automatically (seconds).

~rate (float, default 10.0):: The rate at which the simulated wheel encoder values and rates should be published (Hz).

Note that the project description data, including the texts, logos, images, and/or trademarks, for each open source project belongs to its rightful owner. If you wish to add or remove any projects, please contact us at [email protected].