Skip to content

Commit

Permalink
More package changes
Browse files Browse the repository at this point in the history
  • Loading branch information
AR2100 committed May 30, 2024
1 parent fd93703 commit 907f271
Show file tree
Hide file tree
Showing 6 changed files with 15 additions and 16 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,7 @@ class RoverDrivetrain : public hardware_interface::SystemInterface
std::string udp_port;

// nanopb
uint8_t buffer[DrivetrainRequest_size];
uint8_t buffer[TeensyMessage_size];
size_t message_length;
};

Expand Down
19 changes: 9 additions & 10 deletions urc_hw/src/hardware_interfaces/rover_drivetrain.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -113,8 +113,8 @@ hardware_interface::return_type RoverDrivetrain::read(
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 All @@ -128,19 +128,18 @@ hardware_interface::return_type RoverDrivetrain::write(
}

TeensyMessage message = TeensyMessage_init_zero;
DrivetrainRequest drivetrainRequest = DrivetrainRequest_init_zero;
// DrivetrainRequest drivetrainRequest = DrivetrainRequest_init_zero;
pb_ostream_t stream = pb_ostream_from_buffer(buffer, sizeof(buffer));

drivetrainRequest.m1Setpoint = velocity_rps_commands[0] * ENCODER_CPR * -1;
drivetrainRequest.m2Setpoint = velocity_rps_commands[0] * ENCODER_CPR * -1;
drivetrainRequest.m3Setpoint = velocity_rps_commands[0] * ENCODER_CPR * -1;
message.payload.driveEncodersMessage.m1Setpoint = velocity_rps_commands[0] * ENCODER_CPR * -1;
message.payload.driveEncodersMessage.m2Setpoint = velocity_rps_commands[0] * ENCODER_CPR * -1;
message.payload.driveEncodersMessage.m3Setpoint = velocity_rps_commands[0] * ENCODER_CPR * -1;

drivetrainRequest.m4Setpoint = velocity_rps_commands[1] * ENCODER_CPR * -1;
drivetrainRequest.m5Setpoint = velocity_rps_commands[1] * ENCODER_CPR * -1;
drivetrainRequest.m6Setpoint = velocity_rps_commands[1] * ENCODER_CPR * -1;
message.payload.driveEncodersMessage.m4Setpoint = velocity_rps_commands[1] * ENCODER_CPR * -1;
message.payload.driveEncodersMessage.m5Setpoint = velocity_rps_commands[1] * ENCODER_CPR * -1;
message.payload.driveEncodersMessage.m6Setpoint = velocity_rps_commands[1] * ENCODER_CPR * -1;

message.messageID = 0;
message.payload.drivetrainRequest = drivetrainRequest;

bool status = pb_encode(&stream, TeensyMessage_fields, &message);
message_length = stream.bytes_written;
Expand Down
2 changes: 1 addition & 1 deletion urc_hw/src/hardware_interfaces/status_light.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -130,7 +130,7 @@ hardware_interface::return_type StatusLight::write(const rclcpp::Time &, const r
statusMessage.greenBlink = (signals[0] == 2 && signals[1] == 1);

message.messageID = 1;
message.payload.newStatusLightCommand = statusMessage;
message.payload.statusLightCommand = statusMessage;

bool status = pb_encode(&stream, TeensyMessage_fields, &message);
message_length = stream.bytes_written;
Expand Down
2 changes: 1 addition & 1 deletion urc_imu/src/libimu_driver/driver.py
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ def add_sentence(self, imu_string, frame_id, timestamp=None):
"Sentence was: %s" % imu_string)
return False

self.get_logger().info("Sentence received: %s" % imu_string)
# self.get_logger().info("Sentence received: %s" % imu_string)
things = re.findall(r"-?[0-9]?[0-9]?[0-9]\.[0-9][0-9]", str(imu_string))
current_imu = Imu()
current_yaw = Int32()
Expand Down
4 changes: 2 additions & 2 deletions urc_nanopb/proto/urc.proto
Original file line number Diff line number Diff line change
Expand Up @@ -31,8 +31,8 @@ message NewStatusLightCommand {
message TeensyMessage {
required int32 messageID = 1;
oneof payload {
DrivetrainRequest drivetrainRequest = 2;
NewStatusLightCommand newStatusLightCommand = 3;
DrivetrainRequest driveEncodersMessage = 2;
NewStatusLightCommand statusLightCommand = 3;
}
}

Expand Down
2 changes: 1 addition & 1 deletion urc_tf/src/world_frame.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ void WorldFrameBroadcaster::GPSCallback(
const sensor_msgs::msg::NavSatFix & msg)
{
if (!baseStationSet) {
RCLCPP_ERROR(this->get_logger(), "Base Station Not Set!");
// RCLCPP_ERROR(this->get_logger(), "Base Station Not Set!");
return;
}
geometry_msgs::msg::TransformStamped t;
Expand Down

0 comments on commit 907f271

Please sign in to comment.