Skip to main content

Documentation Index

Fetch the complete documentation index at: https://mintlify.com/Dhruv2012/Autonomous-Farm-Robot/llms.txt

Use this file to discover all available pages before exploring further.

The autonomous_drive package is the core navigation layer of AGRIBOT. It contains Python scripts implementing three cooperating ROS nodes that transform raw GPS and magnetometer data into motor velocity commands, plus an action-based waypoint patrol node. The nodes are intentionally separated by concern: coordinate conversion happens in one node, sensor filtering and angle computation in a second, and velocity command generation in a third. This pipeline design makes it easy to inspect or replace any stage independently.

Node: gps_converter (GPS_data_conversion.py)

The gps_converter node is the entry point for all positional data. It converts raw WGS84 latitude/longitude readings into a local Cartesian XY frame, computes the Euclidean distance and bearing to the goal, and republishes that information for downstream nodes. Node initialization — the node prompts the operator for the target coordinates at startup before entering the ROS spin loop:
rospy.init_node('gps_converter')
# Prompts user at startup:
Goal_latitude  = float(input("Enter Goal Latitude:"))
Goal_longitude = float(input("Enter Goal Longitude:"))
The coordinate projection uses a Mercator-based ll2xy() function (AlvinXY) that converts latitude/longitude pairs to local metres relative to a dynamic origin. The origin is updated in real time from a reference GPS receiver mounted at a fixed pole on the field boundary. Subscriptions:
TopicMessage TypeCallbackDescription
/agribot/fixNavSatFixget_xy_based_on_lat_long()Current robot GPS position
/Pole/fixNavSatFixpublishing_OriginGPS()Reference GPS at the field origin pole
Publications:
TopicMessage TypeDescription
/distanceFloat64Euclidean distance to goal in metres
angleOGFloat64Bearing angle from current position to goal (degrees, atan2-based)
/currentPosePoseCurrent XY position expressed as a Pose message (position.x, position.y)
goal_GPSNavSatFixGoal coordinates packaged as NavSatFix for Mapviz visualization
rosrun autonomous_drive GPS_data_conversion.py

Node: data_manipulation (data_manipulation.py)

The data_manipulation node fuses magnetometer heading with the GPS bearing computed by gps_converter. Raw magnetometer readings are noisy, so the node applies a Moving Median filter over a window of 7 samples before using the heading in navigation calculations. Subscriptions:
TopicMessage TypeCallbackDescription
/magneticVector3Stampedcallback()Raw magnetometer readings from libhector_gazebo_ros_magnetic.so
/currentPosePoseangle_to_move()Current XY position from gps_converter
angleOGFloat64angleassignment()Cached bearing-to-goal from gps_converter
Publications:
TopicMessage TypeDescription
FilteredheadingFloat64Moving Median filtered magnetometer heading (degrees)
RawheadingFloat64Unfiltered raw heading computed from atan2(y, x) of the magnetic vector
/angleFloat64Corrected angle-to-move sent to the drive controller
The corrected angle-to-move is computed in angle_to_move() by combining the cached GPS bearing with the filtered magnetic heading and normalising the result to the [-180, 180] range:
if angle_between_origin_to_goal < 0:
    angleToMove = (-1) * (abs(angle_between_origin_to_goal) + Current_heading) - 90
else:
    angleToMove = abs(angle_between_origin_to_goal) - Current_heading - 90
rosrun autonomous_drive data_manipulation.py

Node: autonomousdrive (autonomus_drive.py)

The autonomousdrive node is the lowest-level node in the pipeline. It reads the heading error and distance-to-goal produced upstream and translates them into Twist velocity commands on /agribot/cmd_vel. A proportional-derivative (PD) control law with kp = 0.01 and kd = 0.5 governs angular corrections while the robot also moves forward. Subscriptions:
TopicMessage TypeCallbackDescription
/angleFloat64callback_for_angle()Heading error in degrees
/distanceFloat64callback_for_distance()Distance to goal in metres
Publications:
TopicMessage TypeDescription
/agribot/cmd_velTwistVelocity commands (linear.x, angular.z)
The GPSAlgoV1() function implements the navigation policy:
  • If |orientation_error| >= 2° and the robot is far from the goal, it rotates while moving forward slowly (linear.x = 0.2).
  • If |orientation_error| > 10°, it rotates in place (linear.x = 0).
  • If |orientation_error| < 2°, it moves straight at full speed (linear.x = 0.4).
  • Angular velocity is clamped to ±0.5 rad/s.
  • When distance_to_goal <= 0.5 m or destination_flag == 1, the node stops all motion and latches the flag.
rosrun autonomous_drive autonomus_drive.py

Node: patrol (AutonomusDriveAction.py)

The patrol node is an alternative high-level navigation client built on the move_base action interface. Rather than the direct GPS pipeline used by autonomousdrive, it sends pre-defined map-frame waypoints to a running move_base server, which handles local path planning and obstacle avoidance internally. Waypoints are defined as a list of [(x, y, z), (qx, qy, qz, qw)] tuples in the map frame:
waypoints = [
    [(-7.33724421822, -0.290481491014, 0.0),
     (0.0, 0.0, 0.997657097136, 0.0684128389565)]
]
The node cycles through the waypoint list indefinitely, sending each as a MoveBaseGoal and waiting for the action server to report success before advancing to the next.
rosrun autonomous_drive AutonomusDriveAction.py
The patrol node requires move_base to be running and a valid occupancy grid map to be available on the /map topic. It is independent of the gps_converter / data_manipulation pipeline.

Running All Nodes Together

The following sequence brings up the complete autonomous navigation stack from a cold start.
1

Start the Gazebo farm simulation

roslaunch agribot_description my_world.launch
This launches Gazebo with Farm.world, spawns AGRIBOT, starts the PID controllers, and opens the gps_converter and sensor_data nodes in xterm windows automatically.
2

Start the wheel controllers (if not using my_world.launch)

roslaunch agribot_control agribot_control.launch
Skip this step if you already launched my_world.launch, which includes agribot_control.launch internally.
3

Run the GPS converter and enter goal coordinates

rosrun autonomous_drive GPS_data_conversion.py
When prompted, enter the goal latitude and longitude for the field waypoint. The node will begin publishing /distance, angleOG, and /currentPose immediately after.
4

Run the data manipulation node

rosrun autonomous_drive data_manipulation.py
This node starts filtering magnetometer readings and publishing the corrected /angle topic consumed by the drive controller.
5

Run the autonomous drive node

rosrun autonomous_drive autonomus_drive.py
AGRIBOT will begin navigating toward the entered goal coordinates. Monitor the terminal output for "Moving straight to goal", "Rotating...", and "Destination reached!!" status messages.
Use rostopic echo /distance and rostopic echo /angle in separate terminals to monitor the navigation pipeline in real time without modifying any source files.

Build docs developers (and LLMs) love