Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Move constants definitions to impl file, add per-stream compression constants #321

Merged
merged 3 commits into from
May 2, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 2 additions & 1 deletion src/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -190,7 +190,7 @@ elseif(GPS STREQUAL "ARDUPILOT")
target_sources(gps_interface PUBLIC
ardupilot/ArduPilotProtocol.cpp
ardupilot/ArduPilotInterface.cpp)
target_link_libraries(gps_interface utils websocket_utils)
target_link_libraries(gps_interface utils websocket_utils rover_common)
else()
target_sources(gps_interface PUBLIC gps/dummy/dummy_gps.cpp)
endif()
Expand Down Expand Up @@ -258,6 +258,7 @@ list(APPEND simulator_libs

add_executable(Rover Rover.cpp)
add_library(rover_common SHARED
Constants.cpp
Globals.cpp
network/websocket/WebSocketServer.cpp
network/websocket/WebSocketProtocol.cpp
Expand Down
151 changes: 151 additions & 0 deletions src/Constants.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,151 @@
#include "Constants.h"

#include "kinematics/DiffDriveKinematics.h"

namespace Constants {
// TODO: make sure these are still accurate with the new arm.
const double SHOULDER_LENGTH = 0.6; // placeholder(m)
const double ELBOW_LENGTH = 0.7; // placeholder(m)

/**
Number of millidegrees per degree
*/
const float MDEG_PER_DEG = 1000;

// TODO: tune these drive constants
const double ROBOT_LENGTH = 1.0;
/**
Distance between left and right wheels.
*/
const double WHEEL_BASE = 2. / 3.;
/**
Effective distance between wheels. Tweaked so that actual rover angular rate roughly matches
the commanded angular rate.
*/
const double EFF_WHEEL_BASE = 1.40; // tweaked to match 2-wheel kinematic model
const double WHEEL_RADIUS = 0.15; // eyeballed
const double PWM_PER_RAD_PER_SEC = 5000; // eyeballed
const double MAX_DRIVE_PWM = 25000; // can be up to 2^15 - 1 (32767) but we have limited it
// because driving at full speed draws a massive amount
// of current that's too much for our power supply (and
// the rover's full speed is somewhat hard to control
// while it's driving)
/**
@brief Maximum tangential velocity for the rover's wheels.

If the rover is driving straight and not turning, this is the maximum forward velocity
(i.e. `dx` in setCmdVel()) of the rover.
*/
const double MAX_WHEEL_VEL = WHEEL_RADIUS * MAX_DRIVE_PWM / PWM_PER_RAD_PER_SEC;
/**
@brief Maximum angular velocity (i.e. `dtheta` in setCmdVel()) of the rover.

Computed assuming that the left wheel is going at full speed backwards while the right wheel
is going at full speed forwards.
*/
const double MAX_DTHETA = kinematics::DiffDriveKinematics(EFF_WHEEL_BASE)
.wheelVelToRobotVel(-MAX_WHEEL_VEL, MAX_WHEEL_VEL)(2);

// TODO: We need to recalibrate the camera, since we replaced it with a different one.
// TODO: rename cameras (in MC as well) as appropriate
const char* MAST_CAMERA_CONFIG_PATH = "../camera-config/MastCameraCalibration.yml";
const robot::types::CameraID MAST_CAMERA_ID =
"upperArm"; // TODO: replace with real camera name

const char* FOREARM_CAMERA_CONFIG_PATH = "../camera-config/ForearmCameraCalibration.yml";
const robot::types::CameraID FOREARM_CAMERA_ID = "rear";

const char* HAND_CAMERA_CONFIG_PATH = "../camera-config/HandCameraCalibration.yml";
const robot::types::CameraID HAND_CAMERA_ID = "front";

/**
@deprecated No need for this constant once we fully switch over the Mission Control PlanViz
*/
const uint16_t PLANVIZ_SERVER_PORT = 9002;
const uint16_t WS_SERVER_PORT = 3001;

/**
WebSocket server endpoint for the mission control protocol.
*/
const char* MC_PROTOCOL_NAME = "/mission-control";
/**
WebSocket server endpoint for the simulator protocol.
*/
const char* SIM_PROTOCOL_NAME = "/simulator";
/**
WebSocket server endpoint for the DGPS protocol.
*/
const char* DGPS_PROTOCOL_NAME = "/dgps";
/**
Websocket server endpoint for ArduPilot protocol
*/
const char* ARDUPILOT_PROTOCOL_NAME = "/ardupilot";

const std::chrono::milliseconds JOINT_POWER_REPEAT_PERIOD(333);
const std::chrono::milliseconds ARM_IK_UPDATE_PERIOD(50);

namespace Nav {
// Distance (m) we could have traveled forward in the time it takes to turn 1 radian
const double RADIAN_COST = EFF_WHEEL_BASE / 2.0;
// Planner stays this far away from obstacles (m)
const double SAFE_RADIUS = Constants::ROBOT_LENGTH * 1.3;
const int MAX_ITERS = 3000; // Max number of nodes expanded during A* search
const double PLAN_RESOLUTION = Constants::ROBOT_LENGTH; // m
const double SEARCH_RADIUS_INCREMENT = Constants::ROBOT_LENGTH * 3;
const double GPS_WAYPOINT_RADIUS = Constants::ROBOT_LENGTH * 1.5;
const double LANDMARK_WAYPOINT_RADIUS = Constants::ROBOT_LENGTH * 1.3;
const double EPS = 2.0; // heuristic weight for weighted A*
} // namespace Nav

// Lidar
namespace Lidar {
const std::string RP_PATH = "/dev/ttyUSB0";
const double MM_PER_M = 1000;
const uint32_t RPLIDAR_A1_BAUDRATE = 115200;
const uint32_t RPLIDAR_S1_BAUDRATE = 256000;
} // namespace Lidar

// Video encoding
namespace video {
const int H264_RF_CONSTANT = 40;
const std::unordered_map<robot::types::CameraID, int> STREAM_RFS = {
{Constants::HAND_CAMERA_ID, 30}};
} // namespace video

// Arm inverse kinematics
namespace arm {
/**
* Percentage of fully extended overall arm length to limit arm extension within.
*/
const double SAFETY_FACTOR = 0.95;

/**
* Maximum commanded end-effector velocity, in m/s
*/
const double MAX_EE_VEL = 0.1;
const double IK_SOLVER_THRESH = 0.001;

const int IK_SOLVER_MAX_ITER = 50;

/**
* The joints corresponding to the motors used for IK in the arm. The ordering in this array is
* the canonical ordering of these joints for IK purposes.
*/
const std::array<robot::types::jointid_t, 2> IK_MOTOR_JOINTS = {
robot::types::jointid_t::shoulder, robot::types::jointid_t::elbow};

/**
* The motors used in IK. The i-th element in this array corresponds to the joint in the i-th
* element of `IK_MOTOR_JOINTS`
*/
const std::array<robot::types::motorid_t, 2> IK_MOTORS = ([]() {
std::array<robot::types::motorid_t, IK_MOTOR_JOINTS.size()> ret{};
for (size_t i = 0; i < IK_MOTOR_JOINTS.size(); i++) {
ret[i] = JOINT_MOTOR_MAP.at(IK_MOTOR_JOINTS[i]);
}
return ret;
})();
} // namespace arm

const double CONTROL_HZ = 10.0;
} // namespace Constants
124 changes: 58 additions & 66 deletions src/Constants.h
Original file line number Diff line number Diff line change
@@ -1,6 +1,5 @@
#pragma once

#include "kinematics/DiffDriveKinematics.h"
#include "world_interface/data.h"

#include <array>
Expand All @@ -10,115 +9,115 @@

#include <frozen/unordered_map.h>

using namespace kinematics;

namespace Constants {
// TODO: make sure these are still accurate with the new arm.
constexpr double SHOULDER_LENGTH = 0.6; // placeholder(m)
constexpr double ELBOW_LENGTH = 0.7; // placeholder(m)
extern const double SHOULDER_LENGTH;
extern const double ELBOW_LENGTH;

/**
Number of millidegrees per degree
*/
constexpr float MDEG_PER_DEG = 1000;
extern const float MDEG_PER_DEG;

// TODO: tune these drive constants
constexpr double ROBOT_LENGTH = 1.0;
// TODO: tune these drive extern constants
extern const double ROBOT_LENGTH;
/**
Distance between left and right wheels.
*/
constexpr double WHEEL_BASE = 2. / 3.;
extern const double WHEEL_BASE;
/**
Effective distance between wheels. Tweaked so that actual rover angular rate roughly matches
the commanded angular rate.
*/
constexpr double EFF_WHEEL_BASE = 1.40; // tweaked to match 2-wheel kinematic model
constexpr double WHEEL_RADIUS = 0.15; // eyeballed
constexpr double PWM_PER_RAD_PER_SEC = 5000; // eyeballed
constexpr double MAX_DRIVE_PWM = 25000; // can be up to 2^15 - 1 (32767) but we have limited it
// because driving at full speed draws a massive amount
// of current that's too much for our power supply (and
// the rover's full speed is somewhat hard to control
// while it's driving)
extern const double EFF_WHEEL_BASE;
extern const double WHEEL_RADIUS;
extern const double PWM_PER_RAD_PER_SEC;
extern const double MAX_DRIVE_PWM;

/**
@brief Maximum tangential velocity for the rover's wheels.

If the rover is driving straight and not turning, this is the maximum forward velocity
(i.e. `dx` in setCmdVel()) of the rover.
*/
constexpr double MAX_WHEEL_VEL = WHEEL_RADIUS * MAX_DRIVE_PWM / PWM_PER_RAD_PER_SEC;
extern const double MAX_WHEEL_VEL;
/**
@brief Maximum angular velocity (i.e. `dtheta` in setCmdVel()) of the rover.

Computed assuming that the left wheel is going at full speed backwards while the right wheel
is going at full speed forwards.
*/
const double MAX_DTHETA = kinematics::DiffDriveKinematics(EFF_WHEEL_BASE)
.wheelVelToRobotVel(-MAX_WHEEL_VEL, MAX_WHEEL_VEL)(2);
extern const double MAX_DTHETA;

// TODO: We need to recalibrate the camera, since we replaced it with a different one.
// TODO: rename cameras (in MC as well) as appropriate
constexpr const char* MAST_CAMERA_CONFIG_PATH = "../camera-config/MastCameraCalibration.yml";
const robot::types::CameraID MAST_CAMERA_ID =
"upperArm"; // TODO: replace with real camera name
extern const char* MAST_CAMERA_CONFIG_PATH;
extern const robot::types::CameraID MAST_CAMERA_ID;

constexpr const char* FOREARM_CAMERA_CONFIG_PATH =
"../camera-config/ForearmCameraCalibration.yml";
const robot::types::CameraID FOREARM_CAMERA_ID = "rear";
extern const char* FOREARM_CAMERA_CONFIG_PATH;
extern const robot::types::CameraID FOREARM_CAMERA_ID;

constexpr const char* HAND_CAMERA_CONFIG_PATH = "../camera-config/HandCameraCalibration.yml";
const robot::types::CameraID HAND_CAMERA_ID = "front";
extern const char* HAND_CAMERA_CONFIG_PATH;
extern const robot::types::CameraID HAND_CAMERA_ID;

/**
@deprecated No need for this constant once we fully switch over the Mission Control PlanViz
*/
constexpr uint16_t PLANVIZ_SERVER_PORT = 9002;
constexpr uint16_t WS_SERVER_PORT = 3001;
extern const uint16_t WS_SERVER_PORT;

/**
WebSocket server endpoint for the mission control protocol.
*/
constexpr const char* MC_PROTOCOL_NAME = "/mission-control";
extern const char* MC_PROTOCOL_NAME;
/**
WebSocket server endpoint for the simulator protocol.
*/
constexpr const char* SIM_PROTOCOL_NAME = "/simulator";
extern const char* SIM_PROTOCOL_NAME;
/**
WebSocket server endpoint for the DGPS protocol.
*/
constexpr const char* DGPS_PROTOCOL_NAME = "/dgps";
extern const char* DGPS_PROTOCOL_NAME;
/**
Websocket server endpoint for ArduPilot protocol
*/
constexpr const char* ARDUPILOT_PROTOCOL_NAME = "/ardupilot";
extern const char* ARDUPILOT_PROTOCOL_NAME;

constexpr std::chrono::milliseconds JOINT_POWER_REPEAT_PERIOD(333);
constexpr std::chrono::milliseconds ARM_IK_UPDATE_PERIOD(50);
extern const std::chrono::milliseconds JOINT_POWER_REPEAT_PERIOD;
extern const std::chrono::milliseconds ARM_IK_UPDATE_PERIOD;

namespace Nav {
// Distance (m) we could have traveled forward in the time it takes to turn 1 radian
constexpr double RADIAN_COST = EFF_WHEEL_BASE / 2.0;
extern const double RADIAN_COST;
// Planner stays this far away from obstacles (m)
constexpr double SAFE_RADIUS = Constants::ROBOT_LENGTH * 1.3;
constexpr int MAX_ITERS = 3000; // Max number of nodes expanded during A* search
constexpr double PLAN_RESOLUTION = Constants::ROBOT_LENGTH; // m
constexpr double SEARCH_RADIUS_INCREMENT = Constants::ROBOT_LENGTH * 3;
constexpr double GPS_WAYPOINT_RADIUS = Constants::ROBOT_LENGTH * 1.5;
constexpr double LANDMARK_WAYPOINT_RADIUS = Constants::ROBOT_LENGTH * 1.3;
constexpr double EPS = 2.0; // heuristic weight for weighted A*
extern const double SAFE_RADIUS;
extern const int MAX_ITERS;
extern const double PLAN_RESOLUTION;
extern const double SEARCH_RADIUS_INCREMENT;
extern const double GPS_WAYPOINT_RADIUS;
extern const double LANDMARK_WAYPOINT_RADIUS;
extern const double EPS;
} // namespace Nav

// Lidar
namespace Lidar {
const std::string RP_PATH = "/dev/ttyUSB0";
constexpr double MM_PER_M = 1000;
constexpr uint32_t RPLIDAR_A1_BAUDRATE = 115200;
constexpr uint32_t RPLIDAR_S1_BAUDRATE = 256000;
extern const std::string RP_PATH;
extern const double MM_PER_M;
extern const uint32_t RPLIDAR_A1_BAUDRATE;
extern const uint32_t RPLIDAR_S1_BAUDRATE;
} // namespace Lidar

// Video encoding
namespace video {
constexpr int H264_RF_CONSTANT = 40;
/**
* @brief Default RF constant for H264 streams, if not specified in STREAM_RFS.
*
* In the range [1, 51], higher values means more compression.
* Should not be below 21, since quality is basically the same but
* bandwidth is much higher.
*/
extern const int H264_RF_CONSTANT;

/**
* @brief Stream-specific RF constants.
*/
extern const std::unordered_map<robot::types::CameraID, int> STREAM_RFS;
} // namespace video

/**
Expand All @@ -139,34 +138,27 @@ namespace arm {
/**
* Percentage of fully extended overall arm length to limit arm extension within.
*/
constexpr double SAFETY_FACTOR = 0.95;
extern const double SAFETY_FACTOR;

/**
* Maximum commanded end-effector velocity, in m/s
*/
constexpr double MAX_EE_VEL = 0.1;
constexpr double IK_SOLVER_THRESH = 0.001;
extern const double MAX_EE_VEL;
extern const double IK_SOLVER_THRESH;

constexpr int IK_SOLVER_MAX_ITER = 50;
extern const int IK_SOLVER_MAX_ITER;

/**
* The joints corresponding to the motors used for IK in the arm. The ordering in this array is
* the canonical ordering of these joints for IK purposes.
*/
constexpr std::array<robot::types::jointid_t, 2> IK_MOTOR_JOINTS = {
robot::types::jointid_t::shoulder, robot::types::jointid_t::elbow};
extern const std::array<robot::types::jointid_t, 2> IK_MOTOR_JOINTS;

/**
* The motors used in IK. The i-th element in this array corresponds to the joint in the i-th
* element of `IK_MOTOR_JOINTS`
*/
constexpr std::array<robot::types::motorid_t, 2> IK_MOTORS = ([]() constexpr {
std::array<robot::types::motorid_t, IK_MOTOR_JOINTS.size()> ret{};
for (size_t i = 0; i < IK_MOTOR_JOINTS.size(); i++) {
ret[i] = JOINT_MOTOR_MAP.at(IK_MOTOR_JOINTS[i]);
}
return ret;
})();
extern const std::array<robot::types::motorid_t, 2> IK_MOTORS;

/**
* Map from motor ids to min and max joint limits in millidegrees
Expand All @@ -183,5 +175,5 @@ constexpr frozen::unordered_map<robot::types::motorid_t, double, IK_MOTORS.size(
{robot::types::motorid_t::elbow, 0.461264}};
} // namespace arm

constexpr double CONTROL_HZ = 10.0;
extern const double CONTROL_HZ;
} // namespace Constants
Loading