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

[hardware] GPS config and drivetrain config #195

Merged
merged 2 commits into from
May 29, 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
8 changes: 4 additions & 4 deletions urc_bringup/config/controller_config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -48,9 +48,9 @@ rover_drivetrain_controller:
left_wheel_names: ["left_wheel"]
right_wheel_names: ["right_wheel"]

wheel_separation: 0.50
wheel_separation: 0.78
#wheels_per_side: 1 # actually 2, but both are controlled by 1 signal
wheel_radius: 0.20
wheel_radius: 0.12

wheel_separation_multiplier: 1.0
left_wheel_radius_multiplier: 1.0
Expand All @@ -75,8 +75,8 @@ rover_drivetrain_controller:
linear.x.has_velocity_limits: true
linear.x.has_acceleration_limits: true
linear.x.has_jerk_limits: false
linear.x.max_velocity: 2.5
linear.x.min_velocity: -2.5
linear.x.max_velocity: 1.0
linear.x.min_velocity: -1.0
linear.x.max_acceleration: 2.5
linear.x.max_jerk: 0.0
linear.x.min_jerk: 0.0
Expand Down
7 changes: 7 additions & 0 deletions urc_bringup/launch/bringup.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,7 @@ def generate_launch_description():
xacro_file, mappings={"use_simulation": "false"}
)
robot_desc = robot_description_config.toxml()
gps_config = os.path.join(get_package_share_directory("urc_bringup"), "config", "nmea_serial_driver.yaml")

control_node = Node(
package="controller_manager",
Expand Down Expand Up @@ -105,6 +106,12 @@ def generate_launch_description():
)
)

launch_gps = Node(
package='nmea_navsat_driver',
executable='nmea_serial_driver',
output='screen',
parameters=[gps_config])

launch_imu = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
os.path.join(pkg_imu_driver, "launch", "imu_serial_driver.launch.py")
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ class RoverDrivetrain : public hardware_interface::SystemInterface
// basic info
const std::string hardware_interface_name;
double publish_encoder_ticks_frequency_;
static constexpr int ENCODER_CPR = 2048;
static constexpr int ENCODER_CPR = 42 * 4;
static constexpr float WHEEL_RADIUS = 0.170;
static constexpr float VEL_TO_COUNTS_FACTOR = ENCODER_CPR / (2 * M_PI * WHEEL_RADIUS);
static constexpr int QPPR = 15562;
Expand Down
6 changes: 3 additions & 3 deletions urc_hw/src/hardware_interfaces/rover_drivetrain.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -112,9 +112,9 @@ hardware_interface::return_type RoverDrivetrain::read(
const rclcpp::Time &,
const rclcpp::Duration &)
{
RCLCPP_INFO(
rclcpp::get_logger(
"test"), "%.5f, %.5f", velocity_rps_commands[0], velocity_rps_commands[1]);
// RCLCPP_INFO(
// rclcpp::get_logger(
// "test"), "%.5f, %.5f", velocity_rps_commands[0], velocity_rps_commands[1]);

return hardware_interface::return_type::OK;
}
Expand Down
Loading