Maintainer | |
---|---|
Jonathan Tyler Boylan | jtylerboylan@outlook.com |
- Contains the launch files for the different components of the SELQIE robot platform.
- Launches full robot suite with custom command terminal.
- SELQIE Hardware:
./src/tmux/selqie.sh
- MuJoCo Simulation:
./src/tmux/selqie_mujoco.sh
- Install ROS Packages:
sudo apt install ros-humble-microstrain-inertial-driver
- Install Apt Packages:
sudo apt install python3-smbus
- Install Bar100 Python Package:
git clone https://github.com/bluerobotics/KellerLD-python ~/.KellerLD
cd ~/.KellerLD && python3 setup.py install --user
- Reads the Bar100 depth sensor via I2C communication.
- Publishers:
Topic | Message Type | Description |
---|---|---|
/bar100/depth |
std_msgs/Float32 |
Sensor depth reading |
/bar100/temperature |
std_msgs/Float32 |
Sensor temperature reading |
- Parameters:
Parameter | Type | Default Value | Description |
---|---|---|---|
i2c_bus |
int |
1 |
I2C bus ID |
frequency |
double |
20.0 |
Sensor publish frequency (in Hz) |
fluid_density |
double |
997.0474 |
Density of the surrounding fluid (kg/m^3) |
gravity |
double |
9.80665 |
Gravity (m/s^2) |
surface_pressure |
double |
1.0 |
Pressure at the surface (bar) |
-
Converts depth reading to a Pose with covariance. Used for EKF fusion in the
robot_localization
package. -
Publishers:
Topic | Message Type | Description |
---|---|---|
/bar100/pose |
geometry_msgs/PoseWithCovarianceStamped |
Output pose with covariance |
- Subscribers:
Topic | Message Type | Description |
---|---|---|
/bar100/depth |
std_msgs/Float32 |
Input depth reading |
- Parameters:
Parameter | Type | Default Value | Description |
---|---|---|---|
frame_id |
string |
"odom" |
Frame of the depth reading |
z_variance |
double |
2.89 |
Depth sensor variance |
- NVIDIA Jetson Orin Shop
- GPIO Pinout
- Jetson Linux Developer Guide (r36.4)
- Configuring Expansion Headers
- Setup GPIO permissions:
sudo groupadd -f -r gpio
sudo usermod -a -G gpio ${USER}
sudo cp ~/selqie_ws/src/tools/99-gpio.rules /etc/udev/rules.d/
- Setup GPIO configuration:
sudo /opt/nvidia/jetson-io/config-by-function.py -o dt pwm5
- ODrive Pro Shop
- Documentation (v0.6.8)
- MJ5208 Motor Shop
- NTCLE300E3502SB Thermistor Shop
- ODrive CAN Guide
- ODrive Pro Pinout
Note: This script is for ODrive firmware v0.6.8. Other firmware versions may not work.
- Plug in USB from the Jetson to the ODrive controller
- Open the Terminal on the the Jetson
- Go to the
tools
folder: $cd ~/selqie_ws/src/tools
- Run the auto-configuration script: $
python3 configure_odrive_mj5208.py <CAN_ID>
- Let the script complete before unplugging
- Install Apt Packages:
sudo apt install libsocketcan-dev can-utils
- Set up CAN boot service (Jetson AGX):
sudo cp ~/selqie_ws/src/tools/load_can.service /etc/systemd/system/
sudo systemctl daemon-reload
sudo systemctl enable load_can.service
sudo systemctl start load_can.service
- Enable CAN interfaces (Jetson AGX):
sudo /opt/nvidia/jetson-io/config-by-function.py -o dt can0 can1
Note: This is run automatically on boot. See tools/load_can.service
for more information
- Open the Terminal on the Jetson
- Go to the
tools
folder: $cd ~/selqie_ws/src/tools
- Run the command: $
sudo ./loadcan_jetson.sh
\
- Receive and transmit frames on the CAN bus.
- Publishers
Topic | Message Type | Description |
---|---|---|
/can/tx |
robot_msgs/CanFrame |
CAN Frame to transmit on the bus |
- Subscribers
Topic | Message Type | Description |
---|---|---|
/can/rx |
robot_msgs/CanFrame |
CAN Frame received on the bus |
- Parameters
Parameter | Type | Default Value | Description |
---|---|---|---|
interface |
string |
"can0" |
CAN Interface Name |
- MuJoCo:
./src/tmux/unitree_a1.sh