Skip to content

Commit

Permalink
Minor cleanup
Browse files Browse the repository at this point in the history
  • Loading branch information
lukeschmitt-tr committed Jul 24, 2024
1 parent 09504e9 commit 63d1868
Show file tree
Hide file tree
Showing 3 changed files with 9 additions and 9 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -151,6 +151,7 @@ class SlateBase : public rclcpp::Node
// Max angular velocity about the z-axis in radians per second
float max_vel_z_ = 1.0;

// Base command bytes containing data about charging and motor torque enabling
uint32_t sys_cmd_ = 0;

// If publish_tf_ is true, this is the broadcaster used to publish the odom->base_link TF
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -48,10 +48,6 @@ bool check(int ret)
{
std::string dev;
err_cnt = 0;
// if (driver.init(dev, 1, B115200))
// RCLCPP_INFO(get_logger(), "chassis init with port %s", dev.c_str());
// else
// RCLCPP_INFO_THROTTLE(get_logger(), 10, "lost chassis com port");
}
return !ret;
}
Expand Down
13 changes: 8 additions & 5 deletions interbotix_ros_slate/interbotix_slate_driver/src/slate_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -95,24 +95,26 @@ void SlateBase::update()
cmd_vel_z_ = 0.0f;
}

// limit velocity commands
cmd_vel_x_ = std::min(max_vel_x_, std::max(-max_vel_x_, cmd_vel_x_));
cmd_vel_z_ = std::min(max_vel_z_, std::max(-max_vel_z_, cmd_vel_z_));

uint32_t light = 0;
// initialize and chassis data and use it to update the driver
base_driver::ChassisData data = {
.cmd_vel_x=cmd_vel_x_,
.cmd_vel_y=0.0,
.cmd_vel_z=cmd_vel_z_,
.light_state=light,
.light_state=0,
.system_state=0};

if (!base_driver::updateChassisInfo(&data)) {
return;
}

uint32_t io = data.io;
// extract and update base system command bytes
sys_cmd_ = data.cmd;

// update battery state every 10 iterations
cnt_++;
auto battery_state = BatteryState();
if (cnt_ % 10 == 0) {
Expand All @@ -124,6 +126,7 @@ void SlateBase::update()
pub_battery_state_->publish(battery_state);
}

// update odometry values
x_vel_ = data.vel_x;
z_omega_ = data.vel_z;

Expand Down Expand Up @@ -194,10 +197,10 @@ bool SlateBase::set_text_callback(
const std::shared_ptr<SetString::Request> req,
const std::shared_ptr<SetString::Response> res)
{
res->message = "Set base screen text to: '" + req->data + "'.";
base_driver::setText(req->data.c_str());
res->message = "Requested to set text to: '" + req->data + "'.";
res->success = true;
RCLCPP_INFO(get_logger(), res->message.c_str());
res->success = true;
return true;
}

Expand Down

0 comments on commit 63d1868

Please sign in to comment.