3#include "../gps/gps_util.h"
4#include "../kinematics/DiffDriveKinematics.h"
5#include "../navtypes.h"
6#include "../network/websocket/WebSocketServer.h"
8#include "motor/base_motor.h"
57 bool initOnlyMotors =
false);
148types::DataPoint<navtypes::point_t>
readGPS();
163types::DataPoint<Eigen::Quaterniond>
readIMU();
224using callbackid_t =
unsigned long long;
226callbackid_t addLimitSwitchCallback(
228 const std::function<
void(
232void removeLimitSwitchCallback(callbackid_t
id);
245template <
unsigned long int N>
246types::DataPoint<navtypes::Vectord<N>>
248 navtypes::Vectord<N> motorPositions;
249 std::optional<types::datatime_t> timestamp;
250 for (
size_t i = 0; i < motors.size(); i++) {
252 if (positionDataPoint.
isValid()) {
253 if (!timestamp.has_value() || timestamp > positionDataPoint.
getTime()) {
254 timestamp = positionDataPoint.
getTime();
256 double position =
static_cast<double>(positionDataPoint.
getData());
257 position *= M_PI / 180.0 / 1000.0;
258 motorPositions(i) = position;
276robot::types::DataPoint<navtypes::gpscoords_t> readGPSCoords();
_Tp power(_Tp __x, _Integer __n, _MonoidOperation __monoid_op)
Represents a set of intrinsic camera parameters.
Definition CameraParams.h:60
Represents the kinematics of a differential drive.
Definition DiffDriveKinematics.h:14
Represents data measured using a sensor at a given time.
Definition data.h:136
T getData() const
Get the value of this data point.
Definition data.h:203
datatime_t getTime() const
Get the time at which the measurement was taken.
Definition data.h:193
bool isValid() const
Check if this measurement is valid.
Definition data.h:183
Namespace for camera access system.
Definition Camera.cpp:13
indication_t
An indication enum, used to command the LED to flash different signals.
Definition data.h:49
std::string CameraID
The type of a camera id.
Definition data.h:46
motorid_t
The motors on the robot.
Definition data.h:57
std::vector< DataPoint< navtypes::point_t > > landmarks_t
A data structure that represents when each landmark was seen.
Definition data.h:41
Collection of functions for manipulating a motor.
Definition ArduPilotInterface.cpp:27
void world_interface_init(std::optional< std::reference_wrapper< net::websocket::SingleClientWSServer > > wsServer, bool initMotorsOnly)
Initialize the world interface.
Definition noop_world.cpp:24
DataPoint< point_t > readGPS()
Get the current position in the global map frame based on a GPS measurement.
Definition gps_common_interface.cpp:19
DataPoint< CameraFrame > readCamera(CameraID cameraID)
Read the latest frame from the given camera.
Definition real_world_interface.cpp:170
bool hasNewCameraFrame(CameraID cameraID, uint32_t oldFrameNum)
Check if a new camera frame from the specified camera is available.
Definition real_world_interface.cpp:160
bool isEmergencyStopped()
Check if the robot has been emergency stopped.
Definition noop_world.cpp:34
std::optional< cam::CameraParams > getCameraIntrinsicParams(CameraID cameraID)
Get the intrinsic params of the specified camera, if it exists.
Definition real_world_interface.cpp:188
DataPoint< pose_t > getTruePose()
Get the ground truth pose, if available.
Definition noop_world.cpp:46
DataPoint< Eigen::Quaterniond > readIMU()
Read the rover orientation from the IMU.
Definition ArduPilotInterface.cpp:28
std::unordered_set< CameraID > getCameras()
Get the IDs of the currently supported cameras.
Definition real_world_interface.cpp:156
std::shared_ptr< robot::base_motor > getMotor(robot::types::motorid_t motor)
Get a pointer to the motor object associated with the motor id.
Definition noop_world.cpp:28
types::DataPoint< navtypes::Vectord< N > > getMotorPositionsRad(const std::array< types::motorid_t, N > &motors)
Get the positions in radians of multiple motors at the same time.
Definition world_interface.h:247
void setMotorVel(robot::types::motorid_t motor, int32_t targetVel)
Sets the velocity of the given motor.
Definition noop_world.cpp:58
WorldInterface
An enum which defines the possible types of world interfaces.
Definition world_interface.h:31
void setMotorPos(motorid_t motor, int32_t targetPos)
Set the target position of the motor.
Definition noop_world.cpp:52
void emergencyStop()
Emergency stop all motors.
Definition noop_world.cpp:32
DataPoint< double > readIMUHeading()
Read the current heading in the global map frame based on an IMU measurement.
Definition gps_common_interface.cpp:14
std::optional< cv::Mat > getCameraExtrinsicParams(CameraID cameraID)
Get the extrinsic params of the specified camera, if it exists.
Definition real_world_interface.cpp:200
bool gpsHasFix()
Check if the GPS sensor has acquired a fix.
Definition gps_common_interface.cpp:44
landmarks_t readLandmarks()
Read measurement from the CV system.
Definition noop_world.cpp:38
const WorldInterface WORLD_INTERFACE
The current world interface being used.
Definition real_world_interface.cpp:29
void setMotorPower(motorid_t motor, double normalizedPWM)
Set the PWM command of the given motor.
Definition noop_world.cpp:50
std::optional< point_t > gpsToMeters(const gpscoords_t &coord)
Convert GPS coordinates into a coordinate on the map frame.
Definition gps_common_interface.cpp:36
types::DataPoint< int32_t > getMotorPos(robot::types::motorid_t motor)
Get the last reported position of the specified motor.
Definition noop_world.cpp:54
void setIndicator(indication_t signal)
Set the robot indicator to indicate the given signal.
Definition noop_world.cpp:60
Represents a GPS coordinate in degrees.
Definition navtypes.h:10