discover_rover module¶
- class discover_rover.Rover(subscribe=False, callback_func=None)¶
Bases:
Config
A class used to instantiate and drive LeoRovers. The LeoRovers are four-wheel drive, operating at a maximum linear speed of 0.4 meters per second, and a maximum angular speed of 60 degrees per second.
Methods
drive
(linear_vel, angular_vel, duration)This function allows the rover to drive, either linearly or angularly.
get_info
()A function that returns information about the rover.
is_available
()Determines whether or not the given sensor is available.
move_backward
(velocity, duration)A function that allows the rover to move backward.
move_forward
(velocity, duration)A function that allows the rover to move forward.
set_callback
(func)A function that sets the callback function to be called whenever the rover moves.
A function that opens a new rosbag file to record all ROS messages published on the /cmd_vel topic.
A function that closes a previously opened rosbag file that has records of ROS messages published on the /cmd_vel topic.
This function subscribes to the cmd_vel topic.
turn_left
(angle, duration)A function that allows the rover to turn left.
turn_right
(angle, duration)A function that allows the rover to turn right.
- drive(linear_vel: float, angular_vel: float, duration: float)¶
This function allows the rover to drive, either linearly or angularly.
- Parameters:
- linear_velfloat
The value in meters per second, of which the rover should move linearly (forward or backward). The maximum accepted value is 0.4 meters per second.
- angular_vel: float
The value in degrees per second, of which the rover should move angularly (turn). The maximum accepted value is 60 degrees per second.
- durationfloat
The number of seconds for which the rover should execute given velocities.
- Returns:
- None
Examples
>>> from rover_api.discover_rover import Rover >>> rover = Rover() >>> rover.drive(0.15, 10, 10) >>> rover.drive( -0.15, -10, 10)
- get_info()¶
A function that returns information about the rover.
- Parameters:
- None
- Returns:
- None
Examples
>>> from rover_api.discover_rover import Rover >>> rover = Rover() >>> info = rover.get_info()
- move_backward(velocity: float, duration: float)¶
A function that allows the rover to move backward.
- Parameters:
- velocityfloat
The value in meters per second, for which the rover should move in reverse. Negative value will move the rover forward. The minimum accepted value is -0.4 meters per second.
- durationfloatUpdate discover_lidar.py
The number of seconds for which the rover should drive backward.
- Returns:
- None
Examples
>>> from rover_api.discover_rover import Rover >>> rover = Rover() >>> rover.move_backward(.10, 10)
- move_forward(velocity: float, duration: float)¶
A function that allows the rover to move forward.
- Parameters:
- velocityfloat
The value in meters per second, for which the rover should move forward. Negative values will move the rover in reverse. The maximum accepted value is 0.4 meters per second.
- durationfloat
The number of seconds for which the rover should drive forward.
- Returns:
- None
Examples
>>> from rover_api.discover_rover import Rover >>> rover = Rover() >>> rover.move_forward(.10, 10)
- set_callback(func)¶
A function that sets the callback function to be called whenever the rover moves. For the callback to be called, subscribe must be set to True in the constructor, or subscribe_to_vel_topic() must have been previously called.
- Parameters:
- funcfunction
This is the new callback function.
- Returns:
- None
Examples
>>> from rover_api.discover_rover import Rover >>> def cb_func(): >>> print("The rover is moving") >>> >>> rover = Rover() >>> rover.set_callback(cb_func) >>> rover.subscribe_to_vel_topic()
- start_recording()¶
A function that opens a new rosbag file to record all ROS messages published on the /cmd_vel topic. For this to work it must be called in conjunction with subscribe_to_vel_topic(), or subscribe must be set to True in the constructor.
- Parameters:
- None
- Returns:
- None
Examples
>>> from rover_api.discover_rover import Rover >>> rover = Rover() >>> rover.subscribe_to_vel_topic() >>> rover.start_recording()Update discover_lidar.py
- stop_recording()¶
A function that closes a previously opened rosbag file that has records of ROS messages published on the /cmd_vel topic.
- Parameters:
- None
- Returns:
- None
Examples
>>> from rover_api.discover_rover import Rover >>> rover = Rover() >>> rover.subscribe_to_vel_topic() >>> rover.start_recording() >>> rover.move_forward(.10, 10) >>> rover.stop_recording()
- subscribe_to_vel_topic()¶
This function subscribes to the cmd_vel topic. This function only needs to be called if there is a callback that should be called whenever the rover moves and/or data needs to be saved to a rosbag. In either event, this function must be called beforehand,or subcribe must be set to True in the constructor.
- Parameters:
- None
- Returns:
- None
Examples
>>> from rover_api.discover_rover import Rover >>> rover = Rover() >>> rover.subscribe_to_vel_topic()
- turn_left(angle: float, duration: float)¶
A function that allows the rover to turn left.
- Parameters:
- velocityfloat
The value in degrees per second, for which the rover should turn left. Negative value turn the rover to the right. The minimum accepted value is 60 degrees per second.
- durationfloat
The number of seconds for which the rover should turn left.
- Returns:
- None
Examples
>>> from rover_api.discover_rover import Rover >>> rover = Rover() >>> rover.turn_left(10, 10)
- turn_right(angle: float, duration: float)¶
A function that allows the rover to turn right.
- Parameters:
- velocityfloat
The value in degrees per second, for which the rover should turn right. Negative value turn the rover to the left. The minimum accepted value is 60 degrees per second.
- durationfloat
The number of seconds for which the rover should turn right.
- Returns:
- None
Examples
>>> from rover_api.discover_rover import Rover >>> rover = Rover() >>> rover.turn_right(10, 10)