Merge "Error more gracefully in logfile sorting if 2 servers fight"
diff --git a/.bazelrc b/.bazelrc
index 3b5ad1f..8290da4 100644
--- a/.bazelrc
+++ b/.bazelrc
@@ -17,12 +17,6 @@
# Use the malloc we want.
build --custom_malloc=//tools/cpp:malloc
-# Use our hermetic Python runtime.
-build --python_top=//tools/python:runtime
-build --noincompatible_use_python_toolchains
-build --noincompatible_py3_is_default
-build --noincompatible_py2_outputs_are_suffixed
-
# Shortcuts for selecting the target platform.
build:k8 --platforms=//tools/platforms:linux_x86
build:roborio --platforms=//tools/platforms:linux_roborio
diff --git a/WORKSPACE b/WORKSPACE
index 23c4580..61991e9 100644
--- a/WORKSPACE
+++ b/WORKSPACE
@@ -125,6 +125,7 @@
"//tools/cpp:cc-toolchain-cortex-m4f",
# Find a good way to select between these two M4F toolchains.
#"//tools/cpp:cc-toolchain-cortex-m4f-k22",
+ "//tools/python:python_toolchain",
)
http_archive(
@@ -230,8 +231,9 @@
# TODO: add frc971.org URL
http_archive(
name = "rules_python",
- sha256 = "778197e26c5fbeb07ac2a2c5ae405b30f6cb7ad1f5510ea6fdac03bded96cc6f",
- url = "https://github.com/bazelbuild/rules_python/releases/download/0.2.0/rules_python-0.2.0.tar.gz",
+ sha256 = "895fa3b03898d7708eb50ed34dcfb71c07866433df6912a6ff4f4fb473048f99",
+ strip_prefix = "rules_python-2b1d6beb4d5d8f59d629597e30e9aa519182d9a9",
+ url = "https://github.com/bazelbuild/rules_python/archive/2b1d6beb4d5d8f59d629597e30e9aa519182d9a9.tar.gz",
)
new_local_repository(
diff --git a/aos/actions/action_test.cc b/aos/actions/action_test.cc
index 1c8e506..e7a3c53 100644
--- a/aos/actions/action_test.cc
+++ b/aos/actions/action_test.cc
@@ -1,8 +1,8 @@
#include <unistd.h>
+#include <chrono>
#include <memory>
#include <thread>
-#include <chrono>
#include "gtest/gtest.h"
@@ -48,8 +48,8 @@
typedef TypedActionFactory<actions::TestActionGoal> Factory;
explicit TestActorNOP(::aos::EventLoop *event_loop)
- : actions::ActorBase<actions::TestActionGoal>(
- event_loop, "/test_action") {}
+ : actions::ActorBase<actions::TestActionGoal>(event_loop,
+ "/test_action") {}
static Factory MakeFactory(::aos::EventLoop *event_loop) {
return Factory(event_loop, "/test_action");
@@ -85,8 +85,8 @@
typedef TypedActionFactory<actions::TestAction2Goal> Factory;
explicit TestActor2Nop(::aos::EventLoop *event_loop)
- : actions::ActorBase<actions::TestAction2Goal>(
- event_loop, "/test_action2") {}
+ : actions::ActorBase<actions::TestAction2Goal>(event_loop,
+ "/test_action2") {}
static Factory MakeFactory(::aos::EventLoop *event_loop) {
return Factory(event_loop, "/test_action2");
@@ -146,14 +146,13 @@
ActionQueue action_queue;
{
- ::aos::Sender<TestActionGoal>::Builder builder =
- goal_sender.MakeBuilder();
+ ::aos::Sender<TestActionGoal>::Builder builder = goal_sender.MakeBuilder();
TestActionGoal::Builder goal_builder =
builder.MakeBuilder<TestActionGoal>();
goal_builder.add_run(971);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ builder.CheckOk(builder.Send(goal_builder.Finish()));
}
TestActorNOP nop_act(actor1_event_loop_.get());
diff --git a/aos/actions/actions.h b/aos/actions/actions.h
index 65dc170..9a62483 100644
--- a/aos/actions/actions.h
+++ b/aos/actions/actions.h
@@ -106,8 +106,8 @@
public:
// A convenient way to refer to the type of our goals.
typedef T GoalType;
- typedef typename std::remove_reference<
- decltype(*static_cast<GoalType *>(nullptr)->params())>::type ParamType;
+ typedef typename std::remove_reference<decltype(
+ *static_cast<GoalType *>(nullptr)->params())>::type ParamType;
TypedAction(typename ::aos::Fetcher<Status> *status_fetcher,
typename ::aos::Sender<GoalType> *goal_sender,
@@ -194,8 +194,8 @@
class TypedActionFactory {
public:
typedef T GoalType;
- typedef typename std::remove_reference<
- decltype(*static_cast<GoalType *>(nullptr)->params())>::type ParamType;
+ typedef typename std::remove_reference<decltype(
+ *static_cast<GoalType *>(nullptr)->params())>::type ParamType;
explicit TypedActionFactory(::aos::EventLoop *event_loop,
const ::std::string &name)
@@ -258,7 +258,7 @@
typename GoalType::Builder goal_builder =
builder.template MakeBuilder<GoalType>();
goal_builder.add_run(0);
- builder.Send(goal_builder.Finish());
+ builder.CheckOk(builder.Send(goal_builder.Finish()));
}
sent_cancel_ = true;
}
@@ -372,7 +372,7 @@
goal_builder.add_run(run_value_);
sent_started_ = true;
- if (!builder.Send(goal_builder.Finish())) {
+ if (builder.Send(goal_builder.Finish()) != RawSender::Error::kOk) {
AOS_LOG(ERROR,
"sending goal for action %" PRIx32 " on queue %.*s failed\n",
run_value_,
diff --git a/aos/actions/actor.h b/aos/actions/actor.h
index a000257..c4f2840 100644
--- a/aos/actions/actor.h
+++ b/aos/actions/actor.h
@@ -20,8 +20,8 @@
class ActorBase {
public:
typedef T GoalType;
- typedef typename std::remove_reference<
- decltype(*static_cast<GoalType *>(nullptr)->params())>::type ParamType;
+ typedef typename std::remove_reference<decltype(
+ *static_cast<GoalType *>(nullptr)->params())>::type ParamType;
ActorBase(::aos::EventLoop *event_loop, const ::std::string &name)
: event_loop_(event_loop),
@@ -40,9 +40,9 @@
status_builder.add_running(0);
status_builder.add_last_running(0);
status_builder.add_success(!abort_);
- if (!builder.Send(status_builder.Finish())) {
- AOS_LOG(ERROR, "Failed to send the status.\n");
- }
+ CHECK_EQ(builder.Send(status_builder.Finish()),
+ aos::RawSender::Error::kOk)
+ << "Failed to send initial status";
});
}
@@ -127,7 +127,8 @@
status_builder.add_running(0);
status_builder.add_last_running(0);
status_builder.add_success(!abort_);
- if (!builder.Send(status_builder.Finish())) {
+ if (builder.Send(status_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(ERROR, "Failed to send the status.\n");
}
break;
@@ -144,7 +145,8 @@
status_builder.add_running(running_id);
status_builder.add_last_running(0);
status_builder.add_success(!abort_);
- if (!builder.Send(status_builder.Finish())) {
+ if (builder.Send(status_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(ERROR, "Failed to send the status.\n");
}
}
@@ -161,7 +163,8 @@
status_builder.add_last_running(running_id);
status_builder.add_success(!abort_);
- if (!builder.Send(status_builder.Finish())) {
+ if (builder.Send(status_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(ERROR, "Failed to send the status.\n");
} else {
AOS_LOG(INFO, "Sending Done status %" PRIx32 "\n", running_id);
diff --git a/aos/aos_send.cc b/aos/aos_send.cc
index 91ffb1c..ffc7957 100644
--- a/aos/aos_send.cc
+++ b/aos/aos_send.cc
@@ -44,7 +44,7 @@
fbb.ForceDefaults(true);
fbb.Finish(aos::JsonToFlatbuffer(std::string_view(argv[1]), channel->schema(),
&fbb));
- sender->Send(fbb.GetSize());
+ sender->CheckOk(sender->Send(fbb.GetSize()));
return 0;
}
diff --git a/aos/events/aos_logging.cc b/aos/events/aos_logging.cc
index bc4513b..5ec7d3d 100644
--- a/aos/events/aos_logging.cc
+++ b/aos/events/aos_logging.cc
@@ -22,8 +22,11 @@
static_cast<::aos::logging::Level>(message_data.level));
builder.add_source_pid(message_data.source);
builder.add_name(name_str);
+ if (send_failure_counter_.failures() > 0) {
+ builder.add_send_failures(send_failure_counter_.failures());
+ }
- message.Send(builder.Finish());
+ send_failure_counter_.Count(message.Send(builder.Finish()));
},
name);
}
diff --git a/aos/events/aos_logging.h b/aos/events/aos_logging.h
index efb2b25..eca07bf 100644
--- a/aos/events/aos_logging.h
+++ b/aos/events/aos_logging.h
@@ -22,6 +22,7 @@
private:
Sender<logging::LogMessageFbs> log_sender_;
std::shared_ptr<logging::LogImplementation> implementation_;
+ SendFailureCounter send_failure_counter_;
};
} // namespace aos
diff --git a/aos/events/event_loop.cc b/aos/events/event_loop.cc
index 51341bb..67c4472 100644
--- a/aos/events/event_loop.cc
+++ b/aos/events/event_loop.cc
@@ -19,8 +19,28 @@
<< configuration::CleanedChannelToString(channel) << ".";
}
}
+
+std::string_view ErrorToString(const RawSender::Error err) {
+ switch (err) {
+ case RawSender::Error::kOk:
+ return "RawSender::Error::kOk";
+ case RawSender::Error::kMessagesSentTooFast:
+ return "RawSender::Error::kMessagesSentTooFast";
+ }
+ LOG(FATAL) << "Unknown error given with code " << static_cast<int>(err);
+}
} // namespace
+std::ostream &operator<<(std::ostream &os, const RawSender::Error err) {
+ os << ErrorToString(err);
+ return os;
+}
+
+void RawSender::CheckOk(const RawSender::Error err) {
+ CHECK_EQ(err, Error::kOk) << "Messages were sent too fast on channel: "
+ << configuration::CleanedChannelToString(channel_);
+}
+
RawSender::RawSender(EventLoop *event_loop, const Channel *channel)
: event_loop_(event_loop),
channel_(channel),
@@ -31,11 +51,10 @@
RawSender::~RawSender() { event_loop_->DeleteSender(this); }
-bool RawSender::DoSend(const SharedSpan data,
- monotonic_clock::time_point monotonic_remote_time,
- realtime_clock::time_point realtime_remote_time,
- uint32_t remote_queue_index,
- const UUID &source_boot_uuid) {
+RawSender::Error RawSender::DoSend(
+ const SharedSpan data, monotonic_clock::time_point monotonic_remote_time,
+ realtime_clock::time_point realtime_remote_time,
+ uint32_t remote_queue_index, const UUID &source_boot_uuid) {
return DoSend(data->data(), data->size(), monotonic_remote_time,
realtime_remote_time, remote_queue_index, source_boot_uuid);
}
@@ -261,7 +280,13 @@
for (RawFetcher *fetcher : fetchers_) {
fetcher->timing_.ResetTimingReport();
}
- timing_report_sender_->Send(timing_report_.span().size());
+ // TODO(milind): If we fail to send, we don't want to reset the timing report.
+ // We would need to move the reset after the send, and then find the correct
+ // timing report and set the reports with it instead of letting the sender do
+ // this. If we failed to send, we wouldn't reset or set the reports, so they
+ // can accumalate until the next send.
+ timing_report_failure_counter_.Count(
+ timing_report_sender_->Send(timing_report_.span().size()));
}
void EventLoop::UpdateTimingReport() {
@@ -421,6 +446,7 @@
if (fetcher_offsets.size() > 0) {
report_builder.add_fetchers(fetchers_offset);
}
+ report_builder.add_send_failures(timing_report_failure_counter_.failures());
fbb.Finish(report_builder.Finish());
timing_report_ = FlatbufferDetachedBuffer<timing::Report>(fbb.Release());
diff --git a/aos/events/event_loop.fbs b/aos/events/event_loop.fbs
index 1434c4e..051f575 100644
--- a/aos/events/event_loop.fbs
+++ b/aos/events/event_loop.fbs
@@ -83,6 +83,9 @@
fetchers:[Fetcher] (id: 4);
timers:[Timer] (id: 5);
phased_loops:[Timer] (id: 6);
+
+ // Total count of Report send failures
+ send_failures:uint64 (id: 7);
}
root_type Report;
diff --git a/aos/events/event_loop.h b/aos/events/event_loop.h
index 61849abe..ac2da4c 100644
--- a/aos/events/event_loop.h
+++ b/aos/events/event_loop.h
@@ -4,6 +4,7 @@
#include <sched.h>
#include <atomic>
+#include <ostream>
#include <string>
#include <string_view>
@@ -138,42 +139,56 @@
public:
using SharedSpan = std::shared_ptr<const absl::Span<const uint8_t>>;
+ enum class [[nodiscard]] Error{
+ // Represents success and no error
+ kOk,
+
+ // Error for messages on channels being sent faster than their
+ // frequency and channel storage duration allow
+ kMessagesSentTooFast};
+
RawSender(EventLoop *event_loop, const Channel *channel);
RawSender(const RawSender &) = delete;
RawSender &operator=(const RawSender &) = delete;
virtual ~RawSender();
- // Sends a message without copying it. The users starts by copying up to
- // size() bytes into the data backed by data(). They then call Send to send.
- // Returns true on a successful send.
- // If provided, monotonic_remote_time, realtime_remote_time, and
- // remote_queue_index are attached to the message and are available in the
- // context on the read side. If they are not populated, the read side will
- // get the sent times instead.
virtual void *data() = 0;
virtual size_t size() = 0;
- bool Send(size_t size);
- bool Send(size_t size, monotonic_clock::time_point monotonic_remote_time,
- realtime_clock::time_point realtime_remote_time,
- uint32_t remote_queue_index, const UUID &source_boot_uuid);
+
+ // Sends a message without copying it. The users starts by copying up to
+ // size() bytes into the data backed by data(). They then call Send to send.
+ // Returns Error::kOk on a successful send, or
+ // Error::kMessagesSentTooFast if messages were sent too fast. If provided,
+ // monotonic_remote_time, realtime_remote_time, and remote_queue_index are
+ // attached to the message and are available in the context on the read side.
+ // If they are not populated, the read side will get the sent times instead.
+ Error Send(size_t size);
+ Error Send(size_t size, monotonic_clock::time_point monotonic_remote_time,
+ realtime_clock::time_point realtime_remote_time,
+ uint32_t remote_queue_index, const UUID &source_boot_uuid);
// Sends a single block of data by copying it.
// The remote arguments have the same meaning as in Send above.
- bool Send(const void *data, size_t size);
- bool Send(const void *data, size_t size,
- monotonic_clock::time_point monotonic_remote_time,
- realtime_clock::time_point realtime_remote_time,
- uint32_t remote_queue_index, const UUID &source_boot_uuid);
+ // Returns Error::kMessagesSentTooFast if messages were sent too fast
+ Error Send(const void *data, size_t size);
+ Error Send(const void *data, size_t size,
+ monotonic_clock::time_point monotonic_remote_time,
+ realtime_clock::time_point realtime_remote_time,
+ uint32_t remote_queue_index, const UUID &source_boot_uuid);
+
+ // CHECKs that no sending Error occurred and logs the channel_ data if
+ // one did
+ void CheckOk(const Error err);
// Sends a single block of data by refcounting it to avoid copies. The data
// must not change after being passed into Send. The remote arguments have the
// same meaning as in Send above.
- bool Send(const SharedSpan data);
- bool Send(const SharedSpan data,
- monotonic_clock::time_point monotonic_remote_time,
- realtime_clock::time_point realtime_remote_time,
- uint32_t remote_queue_index, const UUID &remote_boot_uuid);
+ Error Send(const SharedSpan data);
+ Error Send(const SharedSpan data,
+ monotonic_clock::time_point monotonic_remote_time,
+ realtime_clock::time_point realtime_remote_time,
+ uint32_t remote_queue_index, const UUID &remote_boot_uuid);
const Channel *channel() const { return channel_; }
@@ -210,21 +225,21 @@
private:
friend class EventLoop;
- virtual bool DoSend(const void *data, size_t size,
- monotonic_clock::time_point monotonic_remote_time,
- realtime_clock::time_point realtime_remote_time,
- uint32_t remote_queue_index,
- const UUID &source_boot_uuid) = 0;
- virtual bool DoSend(size_t size,
- monotonic_clock::time_point monotonic_remote_time,
- realtime_clock::time_point realtime_remote_time,
- uint32_t remote_queue_index,
- const UUID &source_boot_uuid) = 0;
- virtual bool DoSend(const SharedSpan data,
- monotonic_clock::time_point monotonic_remote_time,
- realtime_clock::time_point realtime_remote_time,
- uint32_t remote_queue_index,
- const UUID &source_boot_uuid);
+ virtual Error DoSend(const void *data, size_t size,
+ monotonic_clock::time_point monotonic_remote_time,
+ realtime_clock::time_point realtime_remote_time,
+ uint32_t remote_queue_index,
+ const UUID &source_boot_uuid) = 0;
+ virtual Error DoSend(size_t size,
+ monotonic_clock::time_point monotonic_remote_time,
+ realtime_clock::time_point realtime_remote_time,
+ uint32_t remote_queue_index,
+ const UUID &source_boot_uuid) = 0;
+ virtual Error DoSend(const SharedSpan data,
+ monotonic_clock::time_point monotonic_remote_time,
+ realtime_clock::time_point realtime_remote_time,
+ uint32_t remote_queue_index,
+ const UUID &source_boot_uuid);
EventLoop *const event_loop_;
const Channel *const channel_;
@@ -236,6 +251,9 @@
ChannelPreallocatedAllocator fbb_allocator_{nullptr, 0, nullptr};
};
+// Needed for compatibility with glog
+std::ostream &operator<<(std::ostream &os, const RawSender::Error err);
+
// Fetches the newest message from a channel.
// This provides a polling based interface for channels.
template <typename T>
@@ -336,14 +354,17 @@
return typename T2::Builder(fbb_);
}
- bool Send(flatbuffers::Offset<T> offset) {
+ RawSender::Error Send(flatbuffers::Offset<T> offset) {
fbb_.Finish(offset);
- const bool result = sender_->Send(fbb_.GetSize());
+ const auto err = sender_->Send(fbb_.GetSize());
// Ensure fbb_ knows it shouldn't access the memory any more.
fbb_ = flatbuffers::FlatBufferBuilder();
- return result;
+ return err;
}
+ // Equivalent to RawSender::CheckOk
+ void CheckOk(const RawSender::Error err) { sender_->CheckOk(err); };
+
// CHECKs that this message was sent.
void CheckSent() {
CHECK(!allocator_->is_allocated()) << ": Message was not sent yet";
@@ -374,11 +395,14 @@
Builder MakeBuilder();
// Sends a prebuilt flatbuffer.
- bool Send(const NonSizePrefixedFlatbuffer<T> &flatbuffer);
+ RawSender::Error Send(const NonSizePrefixedFlatbuffer<T> &flatbuffer);
// Sends a prebuilt flatbuffer which was detached from a Builder created via
// MakeBuilder() on this object.
- bool SendDetached(FlatbufferDetachedBuffer<T> detached);
+ RawSender::Error SendDetached(FlatbufferDetachedBuffer<T> detached);
+
+ // Equivalent to RawSender::CheckOk
+ void CheckOk(const RawSender::Error err) { sender_->CheckOk(err); };
// Returns the name of the underlying queue.
const Channel *channel() const { return sender_->channel(); }
@@ -405,6 +429,22 @@
std::unique_ptr<RawSender> sender_;
};
+// Class for keeping a count of send failures on a certain channel
+class SendFailureCounter {
+ public:
+ inline void Count(const RawSender::Error err) {
+ failures_ += static_cast<size_t>(err != RawSender::Error::kOk);
+ just_failed_ = (err != RawSender::Error::kOk);
+ }
+
+ inline size_t failures() const { return failures_; }
+ inline bool just_failed() const { return just_failed_; }
+
+ private:
+ size_t failures_ = 0;
+ bool just_failed_ = false;
+};
+
// Interface for timers.
class TimerHandler {
public:
@@ -505,13 +545,13 @@
virtual monotonic_clock::time_point monotonic_now() = 0;
virtual realtime_clock::time_point realtime_now() = 0;
- // Returns true if the channel exists in the configuration.
template <typename T>
const Channel *GetChannel(const std::string_view channel_name) {
return configuration::GetChannel(configuration(), channel_name,
T::GetFullyQualifiedName(), name(), node(),
true);
}
+ // Returns true if the channel exists in the configuration.
template <typename T>
bool HasChannel(const std::string_view channel_name) {
return GetChannel<T>(channel_name) != nullptr;
@@ -807,6 +847,8 @@
// If true, don't send out timing reports.
bool skip_timing_report_ = false;
+ SendFailureCounter timing_report_failure_counter_;
+
absl::btree_set<const Channel *> taken_watchers_, taken_senders_;
};
diff --git a/aos/events/event_loop_param_test.cc b/aos/events/event_loop_param_test.cc
index 2749f60..30e293d 100644
--- a/aos/events/event_loop_param_test.cc
+++ b/aos/events/event_loop_param_test.cc
@@ -86,7 +86,7 @@
aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
builder.add_value(200);
- ASSERT_TRUE(msg.Send(builder.Finish()));
+ msg.CheckOk(msg.Send(builder.Finish()));
});
loop2->MakeWatcher("/test", [&](const TestMessage &message) {
@@ -121,7 +121,7 @@
builder.add_value(200);
detached = msg.Detach(builder.Finish());
}
- ASSERT_TRUE(sender.SendDetached(std::move(detached)));
+ sender.CheckOk(sender.SendDetached(std::move(detached)));
auto fetcher = loop2->MakeFetcher<TestMessage>("/test");
ASSERT_TRUE(fetcher.Fetch());
@@ -142,7 +142,7 @@
aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
- ASSERT_TRUE(msg.Send(builder.Finish()));
+ msg.CheckOk(msg.Send(builder.Finish()));
});
loop2->MakeNoArgWatcher<TestMessage>("/test", [&]() {
@@ -173,7 +173,7 @@
aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
builder.add_value(200);
- ASSERT_TRUE(msg.Send(builder.Finish()));
+ msg.CheckOk(msg.Send(builder.Finish()));
});
aos::Fetcher<TestMessage> fetcher = loop2->MakeFetcher<TestMessage>("/test");
@@ -203,7 +203,7 @@
aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
builder.add_value(200);
- ASSERT_TRUE(msg.Send(builder.Finish()));
+ msg.CheckOk(msg.Send(builder.Finish()));
});
loop2->MakeWatcher("/test", std::function<void(const TestMessage &)>(
@@ -235,13 +235,13 @@
aos::Sender<TestMessage>::Builder msg = sender1.MakeBuilder();
TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
builder.add_value(200);
- ASSERT_TRUE(msg.Send(builder.Finish()));
+ msg.CheckOk(msg.Send(builder.Finish()));
}
{
aos::Sender<TestMessage>::Builder msg = sender2.MakeBuilder();
TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
builder.add_value(200);
- ASSERT_TRUE(msg.Send(builder.Finish()));
+ msg.CheckOk(msg.Send(builder.Finish()));
}
});
@@ -285,7 +285,7 @@
aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
builder.add_value(200);
- ASSERT_TRUE(msg.Send(builder.Finish()));
+ msg.CheckOk(msg.Send(builder.Finish()));
EXPECT_TRUE(fetcher.Fetch());
ASSERT_FALSE(fetcher.get() == nullptr);
@@ -339,7 +339,7 @@
aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
builder.add_value(199);
- ASSERT_TRUE(msg.Send(builder.Finish()));
+ msg.CheckOk(msg.Send(builder.Finish()));
}
loop2->OnRun([&]() {
@@ -347,13 +347,13 @@
aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
builder.add_value(200);
- ASSERT_TRUE(msg.Send(builder.Finish()));
+ msg.CheckOk(msg.Send(builder.Finish()));
}
{
aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
builder.add_value(201);
- ASSERT_TRUE(msg.Send(builder.Finish()));
+ msg.CheckOk(msg.Send(builder.Finish()));
}
});
@@ -376,13 +376,13 @@
aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
builder.add_value(200);
- ASSERT_TRUE(msg.Send(builder.Finish()));
+ msg.CheckOk(msg.Send(builder.Finish()));
}
{
aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
builder.add_value(201);
- ASSERT_TRUE(msg.Send(builder.Finish()));
+ msg.CheckOk(msg.Send(builder.Finish()));
}
loop2->MakeWatcher("/test", [&](const TestMessage &message) {
@@ -413,13 +413,13 @@
aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
builder.add_value(200);
- ASSERT_TRUE(msg.Send(builder.Finish()));
+ msg.CheckOk(msg.Send(builder.Finish()));
}
{
aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
builder.add_value(201);
- ASSERT_TRUE(msg.Send(builder.Finish()));
+ msg.CheckOk(msg.Send(builder.Finish()));
}
// Add a timer to actually quit.
@@ -451,13 +451,13 @@
aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
builder.add_value(200);
- ASSERT_TRUE(msg.Send(builder.Finish()));
+ msg.CheckOk(msg.Send(builder.Finish()));
}
{
aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
builder.add_value(201);
- ASSERT_TRUE(msg.Send(builder.Finish()));
+ msg.CheckOk(msg.Send(builder.Finish()));
}
auto fetcher = loop2->MakeFetcher<TestMessage>("/test");
@@ -492,13 +492,13 @@
aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
builder.add_value(200);
- ASSERT_TRUE(msg.Send(builder.Finish()));
+ msg.CheckOk(msg.Send(builder.Finish()));
}
{
aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
builder.add_value(201);
- ASSERT_TRUE(msg.Send(builder.Finish()));
+ msg.CheckOk(msg.Send(builder.Finish()));
}
auto fetcher = loop2->MakeFetcher<TestMessage>("/test");
@@ -536,13 +536,13 @@
aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
builder.add_value(200);
- ASSERT_TRUE(msg.Send(builder.Finish()));
+ msg.CheckOk(msg.Send(builder.Finish()));
}
{
aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
builder.add_value(201);
- ASSERT_TRUE(msg.Send(builder.Finish()));
+ msg.CheckOk(msg.Send(builder.Finish()));
}
auto fetcher = loop2->MakeFetcher<TestMessage>("/test");
@@ -557,19 +557,19 @@
aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
builder.add_value(202);
- ASSERT_TRUE(msg.Send(builder.Finish()));
+ msg.CheckOk(msg.Send(builder.Finish()));
}
{
aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
builder.add_value(203);
- ASSERT_TRUE(msg.Send(builder.Finish()));
+ msg.CheckOk(msg.Send(builder.Finish()));
}
{
aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
builder.add_value(204);
- ASSERT_TRUE(msg.Send(builder.Finish()));
+ msg.CheckOk(msg.Send(builder.Finish()));
}
if (fetcher.FetchNext()) {
@@ -603,14 +603,14 @@
aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
builder.add_value(100);
- ASSERT_TRUE(msg.Send(builder.Finish()));
+ msg.CheckOk(msg.Send(builder.Finish()));
}
{
aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
builder.add_value(200);
- ASSERT_TRUE(msg.Send(builder.Finish()));
+ msg.CheckOk(msg.Send(builder.Finish()));
}
ASSERT_TRUE(fetcher.FetchNext());
@@ -637,7 +637,7 @@
aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
builder.add_value(1);
- ASSERT_TRUE(msg.Send(builder.Finish()));
+ msg.CheckOk(msg.Send(builder.Finish()));
}
ASSERT_TRUE(fetcher.Fetch());
EXPECT_EQ(1, fetcher.get()->value());
@@ -645,7 +645,7 @@
aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
builder.add_value(i + 2);
- ASSERT_TRUE(msg.Send(builder.Finish()));
+ msg.CheckOk(msg.Send(builder.Finish()));
}
EXPECT_EQ(1, fetcher.get()->value());
}
@@ -663,7 +663,7 @@
aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
builder.add_value(i);
- ASSERT_TRUE(msg.Send(builder.Finish()));
+ msg.CheckOk(msg.Send(builder.Finish()));
};
std::vector<Fetcher<TestMessage>> fetchers;
for (int i = 0; i < 10; ++i) {
@@ -943,7 +943,7 @@
aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
builder.add_value(200);
- ASSERT_TRUE(msg.Send(builder.Finish()));
+ msg.CheckOk(msg.Send(builder.Finish()));
});
Run();
@@ -988,7 +988,7 @@
aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
builder.add_value(200);
- ASSERT_TRUE(msg.Send(builder.Finish()));
+ msg.CheckOk(msg.Send(builder.Finish()));
});
Run();
@@ -1393,7 +1393,7 @@
aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
builder.add_value(200);
- ASSERT_TRUE(msg.Send(builder.Finish()));
+ msg.CheckOk(msg.Send(builder.Finish()));
});
bool triggered = false;
@@ -1493,7 +1493,7 @@
aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
builder.add_value(200);
- ASSERT_TRUE(msg.Send(builder.Finish()));
+ msg.CheckOk(msg.Send(builder.Finish()));
});
bool triggered = false;
@@ -1821,7 +1821,7 @@
aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
builder.add_value(200 + i);
- ASSERT_TRUE(msg.Send(builder.Finish()));
+ msg.CheckOk(msg.Send(builder.Finish()));
}
});
@@ -1906,7 +1906,7 @@
aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
builder.add_value(200 + i);
- ASSERT_TRUE(msg.Send(builder.Finish()));
+ msg.CheckOk(msg.Send(builder.Finish()));
}
});
@@ -1975,7 +1975,7 @@
aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
builder.add_value(200 + i);
- ASSERT_TRUE(msg.Send(builder.Finish()));
+ msg.CheckOk(msg.Send(builder.Finish()));
}
});
@@ -2063,7 +2063,8 @@
loop3->configuration(), "/test", "aos.TestMessage", "", nullptr));
loop2->OnRun([&]() {
- EXPECT_TRUE(sender->Send(kMessage.span().data(), kMessage.span().size()));
+ EXPECT_EQ(sender->Send(kMessage.span().data(), kMessage.span().size()),
+ RawSender::Error::kOk);
});
bool happened = false;
@@ -2113,8 +2114,9 @@
loop3->configuration(), "/test", "aos.TestMessage", "", nullptr));
loop2->OnRun([&]() {
- EXPECT_TRUE(sender->Send(std::make_shared<absl::Span<const uint8_t>>(
- kMessage.span().data(), kMessage.span().size())));
+ EXPECT_EQ(sender->Send(std::make_shared<absl::Span<const uint8_t>>(
+ kMessage.span().data(), kMessage.span().size())),
+ RawSender::Error::kOk);
});
bool happened = false;
@@ -2171,9 +2173,10 @@
loop3->configuration(), "/test", "aos.TestMessage", "", nullptr));
loop2->OnRun([&]() {
- EXPECT_TRUE(sender->Send(kMessage.span().data(), kMessage.span().size(),
- monotonic_remote_time, realtime_remote_time,
- remote_queue_index, source_boot_uuid));
+ EXPECT_EQ(sender->Send(kMessage.span().data(), kMessage.span().size(),
+ monotonic_remote_time, realtime_remote_time,
+ remote_queue_index, source_boot_uuid),
+ RawSender::Error::kOk);
});
bool happened = false;
@@ -2217,7 +2220,8 @@
const aos::monotonic_clock::time_point monotonic_now = loop1->monotonic_now();
const aos::realtime_clock::time_point realtime_now = loop1->realtime_now();
- EXPECT_TRUE(sender->Send(kMessage.span().data(), kMessage.span().size()));
+ EXPECT_EQ(sender->Send(kMessage.span().data(), kMessage.span().size()),
+ RawSender::Error::kOk);
EXPECT_GE(sender->monotonic_sent_time(), monotonic_now);
EXPECT_LE(sender->monotonic_sent_time(),
@@ -2227,7 +2231,8 @@
realtime_now + chrono::milliseconds(100));
EXPECT_EQ(sender->sent_queue_index(), 0u);
- EXPECT_TRUE(sender->Send(kMessage.span().data(), kMessage.span().size()));
+ EXPECT_EQ(sender->Send(kMessage.span().data(), kMessage.span().size()),
+ RawSender::Error::kOk);
EXPECT_GE(sender->monotonic_sent_time(), monotonic_now);
EXPECT_LE(sender->monotonic_sent_time(),
@@ -2382,7 +2387,7 @@
loop1->OnRun([&]() {
aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
- ASSERT_TRUE(msg.Send(builder.Finish()));
+ msg.CheckOk(msg.Send(builder.Finish()));
});
loop1->MakeWatcher("/test", [&](const TestMessage &) {
@@ -2405,7 +2410,7 @@
loop1->OnRun([&]() {
aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
- ASSERT_TRUE(msg.Send(builder.Finish()));
+ msg.CheckOk(msg.Send(builder.Finish()));
});
loop1->MakeWatcher("/test", [&](const TestMessage &) {
@@ -2558,7 +2563,7 @@
auto builder = sender1.MakeBuilder();
FlatbufferDetachedBuffer<TestMessage> detached =
builder.Detach(builder.MakeBuilder<TestMessage>().Finish());
- EXPECT_DEATH(sender2.SendDetached(std::move(detached)),
+ EXPECT_DEATH(sender2.CheckOk(sender2.SendDetached(std::move(detached))),
"May only send the buffer detached from this Sender");
}
diff --git a/aos/events/event_loop_tmpl.h b/aos/events/event_loop_tmpl.h
index 1a02495..0b08dc0 100644
--- a/aos/events/event_loop_tmpl.h
+++ b/aos/events/event_loop_tmpl.h
@@ -132,17 +132,18 @@
return false;
}
-inline bool RawSender::Send(size_t size) {
+inline RawSender::Error RawSender::Send(size_t size) {
return Send(size, monotonic_clock::min_time, realtime_clock::min_time,
0xffffffffu, event_loop_->boot_uuid());
}
-inline bool RawSender::Send(
+inline RawSender::Error RawSender::Send(
size_t size, aos::monotonic_clock::time_point monotonic_remote_time,
aos::realtime_clock::time_point realtime_remote_time,
uint32_t remote_queue_index, const UUID &uuid) {
- if (DoSend(size, monotonic_remote_time, realtime_remote_time,
- remote_queue_index, uuid)) {
+ const auto err = DoSend(size, monotonic_remote_time, realtime_remote_time,
+ remote_queue_index, uuid);
+ if (err == RawSender::Error::kOk) {
if (timing_.sender) {
timing_.size.Add(size);
timing_.sender->mutate_count(timing_.sender->count() + 1);
@@ -152,23 +153,23 @@
static_cast<int>(ftrace_prefix_.size()), ftrace_prefix_.data(),
static_cast<int64_t>(monotonic_sent_time().time_since_epoch().count()),
sent_queue_index());
- return true;
}
- return false;
+ return err;
}
-inline bool RawSender::Send(const void *data, size_t size) {
+inline RawSender::Error RawSender::Send(const void *data, size_t size) {
return Send(data, size, monotonic_clock::min_time, realtime_clock::min_time,
0xffffffffu, event_loop_->boot_uuid());
}
-inline bool RawSender::Send(
+inline RawSender::Error RawSender::Send(
const void *data, size_t size,
aos::monotonic_clock::time_point monotonic_remote_time,
aos::realtime_clock::time_point realtime_remote_time,
uint32_t remote_queue_index, const UUID &uuid) {
- if (DoSend(data, size, monotonic_remote_time, realtime_remote_time,
- remote_queue_index, uuid)) {
+ const auto err = DoSend(data, size, monotonic_remote_time,
+ realtime_remote_time, remote_queue_index, uuid);
+ if (err == RawSender::Error::kOk) {
if (timing_.sender) {
timing_.size.Add(size);
timing_.sender->mutate_count(timing_.sender->count() + 1);
@@ -178,24 +179,24 @@
static_cast<int>(ftrace_prefix_.size()), ftrace_prefix_.data(),
static_cast<int64_t>(monotonic_sent_time().time_since_epoch().count()),
sent_queue_index());
- return true;
}
- return false;
+ return err;
}
-inline bool RawSender::Send(const SharedSpan data) {
+inline RawSender::Error RawSender::Send(const SharedSpan data) {
return Send(std::move(data), monotonic_clock::min_time,
realtime_clock::min_time, 0xffffffffu, event_loop_->boot_uuid());
}
-inline bool RawSender::Send(
+inline RawSender::Error RawSender::Send(
const SharedSpan data,
aos::monotonic_clock::time_point monotonic_remote_time,
aos::realtime_clock::time_point realtime_remote_time,
uint32_t remote_queue_index, const UUID &uuid) {
const size_t size = data->size();
- if (DoSend(std::move(data), monotonic_remote_time, realtime_remote_time,
- remote_queue_index, uuid)) {
+ const auto err = DoSend(std::move(data), monotonic_remote_time,
+ realtime_remote_time, remote_queue_index, uuid);
+ if (err == Error::kOk) {
if (timing_.sender) {
timing_.size.Add(size);
timing_.sender->mutate_count(timing_.sender->count() + 1);
@@ -205,9 +206,8 @@
static_cast<int>(ftrace_prefix_.size()), ftrace_prefix_.data(),
static_cast<int64_t>(monotonic_sent_time().time_since_epoch().count()),
sent_queue_index());
- return true;
}
- return false;
+ return err;
}
inline monotonic_clock::time_point TimerHandler::Call(
@@ -371,12 +371,13 @@
};
template <typename T>
-bool Sender<T>::Send(const NonSizePrefixedFlatbuffer<T> &flatbuffer) {
+RawSender::Error Sender<T>::Send(
+ const NonSizePrefixedFlatbuffer<T> &flatbuffer) {
return sender_->Send(flatbuffer.span().data(), flatbuffer.span().size());
}
template <typename T>
-bool Sender<T>::SendDetached(FlatbufferDetachedBuffer<T> detached) {
+RawSender::Error Sender<T>::SendDetached(FlatbufferDetachedBuffer<T> detached) {
CHECK_EQ(static_cast<void *>(detached.span().data() + detached.span().size() -
sender_->size()),
sender_->data())
diff --git a/aos/events/logging/log_reader.cc b/aos/events/logging/log_reader.cc
index a757303..63eba05 100644
--- a/aos/events/logging/log_reader.cc
+++ b/aos/events/logging/log_reader.cc
@@ -1424,7 +1424,7 @@
// Send! Use the replayed queue index here instead of the logged queue index
// for the remote queue index. This makes re-logging work.
- const bool sent = sender->Send(
+ const auto err = sender->Send(
RawSender::SharedSpan(timestamped_message.data,
×tamped_message.data->span),
timestamped_message.monotonic_remote_time.time,
@@ -1434,7 +1434,7 @@
channel_source_state_[timestamped_message.channel_index])
->event_loop_->boot_uuid()
: event_loop_->boot_uuid()));
- if (!sent) return false;
+ if (err != RawSender::Error::kOk) return false;
if (queue_index_map_[timestamped_message.channel_index]) {
CHECK_EQ(timestamped_message.monotonic_event_time.boot, boot_count());
@@ -1455,7 +1455,8 @@
ContiguousSentTimestamp *back =
&queue_index_map_[timestamped_message.channel_index]->back();
if ((back->starting_queue_index - back->actual_queue_index) ==
- (timestamped_message.queue_index.index - sender->sent_queue_index())) {
+ (timestamped_message.queue_index.index -
+ sender->sent_queue_index())) {
back->ending_queue_index = timestamped_message.queue_index.index;
back->ending_monotonic_event_time =
timestamped_message.monotonic_event_time.time;
@@ -1597,7 +1598,8 @@
// Send out all timestamps at the currently scheduled time.
while (remote_timestamps_.front().monotonic_timestamp_time ==
scheduled_time_) {
- sender_.Send(std::move(remote_timestamps_.front().remote_message));
+ CHECK_EQ(sender_.Send(std::move(remote_timestamps_.front().remote_message)),
+ RawSender::Error::kOk);
remote_timestamps_.pop_front();
if (remote_timestamps_.empty()) {
break;
diff --git a/aos/events/logging/logfile_sorting.cc b/aos/events/logging/logfile_sorting.cc
index 7f98fa8..7610295 100644
--- a/aos/events/logging/logfile_sorting.cc
+++ b/aos/events/logging/logfile_sorting.cc
@@ -15,6 +15,9 @@
#include "openssl/sha.h"
#include "sys/stat.h"
+DEFINE_bool(quiet_sorting, false,
+ "If true, sort with minimal messages about truncated files.");
+
namespace aos {
namespace logger {
namespace chrono = std::chrono;
@@ -343,11 +346,13 @@
// resources, so close a big batch at once periodically.
part_readers.clear();
}
- part_readers.emplace_back(part);
+ part_readers.emplace_back(part, FLAGS_quiet_sorting);
std::optional<SizePrefixedFlatbufferVector<LogFileHeader>> log_header =
ReadHeader(&part_readers.back());
if (!log_header) {
- LOG(WARNING) << "Skipping " << part << " without a header";
+ if (!FLAGS_quiet_sorting) {
+ LOG(WARNING) << "Skipping " << part << " without a header";
+ }
corrupted.emplace_back(part);
continue;
}
@@ -462,7 +467,9 @@
std::optional<SizePrefixedFlatbufferVector<MessageHeader>> first_message =
ReadNthMessage(part, 0);
if (!first_message) {
- LOG(WARNING) << "Skipping " << part << " without any messages";
+ if (!FLAGS_quiet_sorting) {
+ LOG(WARNING) << "Skipping " << part << " without any messages";
+ }
corrupted.emplace_back(part);
continue;
}
diff --git a/aos/events/logging/logfile_utils.cc b/aos/events/logging/logfile_utils.cc
index 0293aa1..59b106e 100644
--- a/aos/events/logging/logfile_utils.cc
+++ b/aos/events/logging/logfile_utils.cc
@@ -336,15 +336,18 @@
return message_header_builder.Finish();
}
-SpanReader::SpanReader(std::string_view filename) : filename_(filename) {
+SpanReader::SpanReader(std::string_view filename, bool quiet)
+ : filename_(filename) {
decoder_ = std::make_unique<DummyDecoder>(filename);
static constexpr std::string_view kXz = ".xz";
static constexpr std::string_view kSnappy = SnappyDecoder::kExtension;
if (filename.substr(filename.size() - kXz.size()) == kXz) {
#if ENABLE_LZMA
- decoder_ = std::make_unique<ThreadedLzmaDecoder>(std::move(decoder_));
+ decoder_ =
+ std::make_unique<ThreadedLzmaDecoder>(std::move(decoder_), quiet);
#else
+ (void)quiet;
LOG(FATAL) << "Reading xz-compressed files not supported on this platform";
#endif
} else if (filename.substr(filename.size() - kSnappy.size()) == kSnappy) {
diff --git a/aos/events/logging/logfile_utils.h b/aos/events/logging/logfile_utils.h
index 3a84726..f2bdc42 100644
--- a/aos/events/logging/logfile_utils.h
+++ b/aos/events/logging/logfile_utils.h
@@ -202,7 +202,7 @@
// Class to read chunks out of a log file.
class SpanReader {
public:
- SpanReader(std::string_view filename);
+ SpanReader(std::string_view filename, bool quiet = false);
std::string_view filename() const { return filename_; }
diff --git a/aos/events/logging/logger_test.cc b/aos/events/logging/logger_test.cc
index 7bf9478..a1e8cc9 100644
--- a/aos/events/logging/logger_test.cc
+++ b/aos/events/logging/logger_test.cc
@@ -3,8 +3,8 @@
#include "absl/strings/str_format.h"
#include "aos/events/event_loop.h"
#include "aos/events/logging/log_reader.h"
-#include "aos/events/logging/snappy_encoder.h"
#include "aos/events/logging/log_writer.h"
+#include "aos/events/logging/snappy_encoder.h"
#include "aos/events/message_counter.h"
#include "aos/events/ping_lib.h"
#include "aos/events/pong_lib.h"
@@ -168,15 +168,15 @@
Logger logger(logger_event_loop.get());
logger.set_polling_period(std::chrono::milliseconds(100));
- logger_event_loop->OnRun(
- [base_name1, base_name2, &logger_event_loop, &logger]() {
+ logger_event_loop->OnRun([base_name1, base_name2, &logger_event_loop,
+ &logger]() {
+ logger.StartLogging(std::make_unique<LocalLogNamer>(
+ base_name1, logger_event_loop.get(), logger_event_loop->node()));
+ EXPECT_DEATH(
logger.StartLogging(std::make_unique<LocalLogNamer>(
- base_name1, logger_event_loop.get(), logger_event_loop->node()));
- EXPECT_DEATH(logger.StartLogging(std::make_unique<LocalLogNamer>(
- base_name2, logger_event_loop.get(),
- logger_event_loop->node())),
- "Already logging");
- });
+ base_name2, logger_event_loop.get(), logger_event_loop->node())),
+ "Already logging");
+ });
event_loop_factory_.RunFor(chrono::milliseconds(20000));
}
}
@@ -398,7 +398,8 @@
ping_sender.MakeBuilder();
examples::Ping::Builder ping_builder =
builder.MakeBuilder<examples::Ping>();
- CHECK(builder.Send(ping_builder.Finish()));
+ CHECK_EQ(builder.Send(ping_builder.Finish()),
+ RawSender::Error::kOk);
});
// 100 ms / 0.05 ms -> 2000 messages. Should be enough to crash it.
@@ -2613,9 +2614,9 @@
}
constexpr std::string_view kCombinedConfigSha1(
- "cad3b6838a518ab29470771a959b89945ee034bc7a738080fd1713a1dce51b1f");
+ "644a3ab079c3ddfb1ef866483cfca9ec015c4142202169081138f72664ffd589");
constexpr std::string_view kSplitConfigSha1(
- "aafdd7e43d1942cce5b3e2dd8c6b9706abf7068a43501625a33b7cdfddf6c932");
+ "20bb9f6ee89519c4bd49986f0afe497d61c71b29d846f2c51f51727c9ef37415");
INSTANTIATE_TEST_SUITE_P(
All, MultinodeLoggerTest,
diff --git a/aos/events/logging/lzma_encoder.cc b/aos/events/logging/lzma_encoder.cc
index e9915af..f32d7e2 100644
--- a/aos/events/logging/lzma_encoder.cc
+++ b/aos/events/logging/lzma_encoder.cc
@@ -149,9 +149,11 @@
total_bytes_ += last_avail_out - stream_.avail_out;
}
-LzmaDecoder::LzmaDecoder(std::unique_ptr<DataDecoder> underlying_decoder)
+LzmaDecoder::LzmaDecoder(std::unique_ptr<DataDecoder> underlying_decoder,
+ bool quiet)
: underlying_decoder_(std::move(underlying_decoder)),
- stream_(LZMA_STREAM_INIT) {
+ stream_(LZMA_STREAM_INIT),
+ quiet_(quiet) {
compressed_data_.resize(kBufSize);
lzma_ret status =
@@ -200,9 +202,13 @@
if (!LzmaCodeIsOk(status, filename())) {
finished_ = true;
if (status == LZMA_DATA_ERROR) {
- LOG(WARNING) << filename() << " is corrupted.";
+ if (!quiet_ || VLOG_IS_ON(1)) {
+ LOG(WARNING) << filename() << " is corrupted.";
+ }
} else if (status == LZMA_BUF_ERROR) {
- LOG(WARNING) << filename() << " is truncated or corrupted.";
+ if (!quiet_ || VLOG_IS_ON(1)) {
+ LOG(WARNING) << filename() << " is truncated or corrupted.";
+ }
} else {
LOG(FATAL) << "Unknown error " << status << " when reading "
<< filename();
@@ -214,8 +220,8 @@
}
ThreadedLzmaDecoder::ThreadedLzmaDecoder(
- std::unique_ptr<DataDecoder> underlying_decoder)
- : decoder_(std::move(underlying_decoder)), decode_thread_([this] {
+ std::unique_ptr<DataDecoder> underlying_decoder, bool quiet)
+ : decoder_(std::move(underlying_decoder), quiet), decode_thread_([this] {
std::unique_lock lock(decode_mutex_);
while (true) {
// Wake if the queue is too small or we are finished.
diff --git a/aos/events/logging/lzma_encoder.h b/aos/events/logging/lzma_encoder.h
index fc6fcb6..7b7010a 100644
--- a/aos/events/logging/lzma_encoder.h
+++ b/aos/events/logging/lzma_encoder.h
@@ -54,9 +54,10 @@
public:
static constexpr std::string_view kExtension = ".xz";
- explicit LzmaDecoder(std::unique_ptr<DataDecoder> underlying_decoder);
- explicit LzmaDecoder(std::string_view filename)
- : LzmaDecoder(std::make_unique<DummyDecoder>(filename)) {}
+ explicit LzmaDecoder(std::unique_ptr<DataDecoder> underlying_decoder,
+ bool quiet = false);
+ explicit LzmaDecoder(std::string_view filename, bool quiet = false)
+ : LzmaDecoder(std::make_unique<DummyDecoder>(filename), quiet) {}
LzmaDecoder(const LzmaDecoder &) = delete;
LzmaDecoder(LzmaDecoder &&other) = delete;
LzmaDecoder &operator=(const LzmaDecoder &) = delete;
@@ -84,6 +85,9 @@
// Flag that represents whether or not all the data from the file has been
// successfully decoded.
bool finished_ = false;
+ // Flag to signal how quiet to be when logging potential issues around
+ // truncation.
+ const bool quiet_ = false;
};
// Decompresses data with liblzma in a new thread, up to a maximum queue
@@ -91,9 +95,10 @@
// or block until more data is queued or the stream finishes.
class ThreadedLzmaDecoder : public DataDecoder {
public:
- explicit ThreadedLzmaDecoder(std::string_view filename)
- : ThreadedLzmaDecoder(std::make_unique<DummyDecoder>(filename)) {}
- explicit ThreadedLzmaDecoder(std::unique_ptr<DataDecoder> underlying_decoder);
+ explicit ThreadedLzmaDecoder(std::string_view filename, bool quiet = false)
+ : ThreadedLzmaDecoder(std::make_unique<DummyDecoder>(filename), quiet) {}
+ explicit ThreadedLzmaDecoder(std::unique_ptr<DataDecoder> underlying_decoder,
+ bool quiet = false);
ThreadedLzmaDecoder(const ThreadedLzmaDecoder &) = delete;
ThreadedLzmaDecoder &operator=(const ThreadedLzmaDecoder &) = delete;
diff --git a/aos/events/ping_lib.cc b/aos/events/ping_lib.cc
index 7a0bfec..900ed0d 100644
--- a/aos/events/ping_lib.cc
+++ b/aos/events/ping_lib.cc
@@ -36,7 +36,7 @@
ping_builder.add_value(count_);
ping_builder.add_send_time(
event_loop_->monotonic_now().time_since_epoch().count());
- CHECK(builder.Send(ping_builder.Finish()));
+ builder.CheckOk(builder.Send(ping_builder.Finish()));
VLOG(2) << "Sending ping";
}
diff --git a/aos/events/pong_lib.cc b/aos/events/pong_lib.cc
index 9d7731d..9f1c855 100644
--- a/aos/events/pong_lib.cc
+++ b/aos/events/pong_lib.cc
@@ -16,7 +16,7 @@
builder.MakeBuilder<examples::Pong>();
pong_builder.add_value(ping.value());
pong_builder.add_initial_send_time(ping.send_time());
- CHECK(builder.Send(pong_builder.Finish()));
+ builder.CheckOk(builder.Send(pong_builder.Finish()));
});
event_loop_->SetRuntimeRealtimePriority(5);
diff --git a/aos/events/shm_event_loop.cc b/aos/events/shm_event_loop.cc
index a215040..ed3d099 100644
--- a/aos/events/shm_event_loop.cc
+++ b/aos/events/shm_event_loop.cc
@@ -547,11 +547,12 @@
shm_event_loop()->CheckCurrentThread();
return lockless_queue_sender_.size();
}
- bool DoSend(size_t length,
- aos::monotonic_clock::time_point monotonic_remote_time,
- aos::realtime_clock::time_point realtime_remote_time,
- uint32_t remote_queue_index,
- const UUID &source_boot_uuid) override {
+
+ Error DoSend(size_t length,
+ aos::monotonic_clock::time_point monotonic_remote_time,
+ aos::realtime_clock::time_point realtime_remote_time,
+ uint32_t remote_queue_index,
+ const UUID &source_boot_uuid) override {
shm_event_loop()->CheckCurrentThread();
CHECK_LE(length, static_cast<size_t>(channel()->max_size()))
<< ": Sent too big a message on "
@@ -565,14 +566,15 @@
wake_upper_.Wakeup(event_loop()->is_running() ? event_loop()->priority()
: 0);
- return true;
+ // TODO(Milind): check for messages sent too fast
+ return Error::kOk;
}
- bool DoSend(const void *msg, size_t length,
- aos::monotonic_clock::time_point monotonic_remote_time,
- aos::realtime_clock::time_point realtime_remote_time,
- uint32_t remote_queue_index,
- const UUID &source_boot_uuid) override {
+ Error DoSend(const void *msg, size_t length,
+ aos::monotonic_clock::time_point monotonic_remote_time,
+ aos::realtime_clock::time_point realtime_remote_time,
+ uint32_t remote_queue_index,
+ const UUID &source_boot_uuid) override {
shm_event_loop()->CheckCurrentThread();
CHECK_LE(length, static_cast<size_t>(channel()->max_size()))
<< ": Sent too big a message on "
@@ -586,7 +588,7 @@
wake_upper_.Wakeup(event_loop()->is_running() ? event_loop()->priority()
: 0);
// TODO(austin): Return an error if we send too fast.
- return true;
+ return RawSender::Error::kOk;
}
absl::Span<char> GetSharedMemory() const {
diff --git a/aos/events/shm_event_loop_test.cc b/aos/events/shm_event_loop_test.cc
index 7e1444b..01ca92b 100644
--- a/aos/events/shm_event_loop_test.cc
+++ b/aos/events/shm_event_loop_test.cc
@@ -144,7 +144,7 @@
aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
builder.add_value(200);
- msg.Send(builder.Finish());
+ msg.CheckOk(msg.Send(builder.Finish()));
}
EXPECT_FALSE(IsRealtime());
@@ -185,7 +185,7 @@
aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
builder.add_value(200);
- msg.Send(builder.Finish());
+ msg.CheckOk(msg.Send(builder.Finish()));
});
factory()->Run();
@@ -280,7 +280,7 @@
auto builder = sender.MakeBuilder();
TestMessage::Builder test_builder(*builder.fbb());
test_builder.add_value(1);
- CHECK(builder.Send(test_builder.Finish()));
+ builder.CheckOk(builder.Send(test_builder.Finish()));
});
factory()->Run();
EXPECT_TRUE(ran);
@@ -317,7 +317,7 @@
auto builder = sender.MakeBuilder();
TestMessage::Builder test_builder(*builder.fbb());
test_builder.add_value(1);
- CHECK(builder.Send(test_builder.Finish()));
+ builder.CheckOk(builder.Send(test_builder.Finish()));
}
ASSERT_TRUE(fetcher.Fetch());
@@ -336,13 +336,13 @@
EXPECT_DEATH(
{
++static_cast<char *>(sender->data())[-1 - i];
- sender->Send(0);
+ sender->CheckOk(sender->Send(0));
},
"Somebody wrote outside the buffer of their message");
EXPECT_DEATH(
{
++static_cast<char *>(sender->data())[sender->size() + i];
- sender->Send(0);
+ sender->CheckOk(sender->Send(0));
},
"Somebody wrote outside the buffer of their message");
}
@@ -361,7 +361,7 @@
auto builder = sender.MakeBuilder();
TestMessage::Builder test_builder(*builder.fbb());
test_builder.add_value(0);
- CHECK(builder.Send(test_builder.Finish()));
+ builder.CheckOk(builder.Send(test_builder.Finish()));
}
EXPECT_DEATH(fetcher.FetchNext(),
"The next message is no longer "
@@ -387,7 +387,7 @@
auto builder = sender.MakeBuilder();
TestMessage::Builder test_builder(*builder.fbb());
test_builder.add_value(0);
- CHECK(builder.Send(test_builder.Finish()));
+ builder.CheckOk(builder.Send(test_builder.Finish()));
}
EXPECT_DEATH(fetcher.FetchNext(),
"The next message is no longer "
@@ -410,7 +410,7 @@
auto builder = sender.MakeBuilder();
TestMessage::Builder test_builder(*builder.fbb());
test_builder.add_value(0);
- CHECK(builder.Send(test_builder.Finish()));
+ builder.CheckOk(builder.Send(test_builder.Finish()));
}
EXPECT_DEATH(fetcher.FetchNext(),
"The next message is no longer "
@@ -429,7 +429,7 @@
auto builder = sender.MakeBuilder();
TestMessage::Builder test_builder(*builder.fbb());
test_builder.add_value(0);
- CHECK(builder.Send(test_builder.Finish()));
+ builder.CheckOk(builder.Send(test_builder.Finish()));
}
EXPECT_DEATH(fetcher.FetchNext(),
"The next message is no longer "
diff --git a/aos/events/simulated_event_loop.cc b/aos/events/simulated_event_loop.cc
index 9e12481..083e246 100644
--- a/aos/events/simulated_event_loop.cc
+++ b/aos/events/simulated_event_loop.cc
@@ -2,6 +2,8 @@
#include <algorithm>
#include <deque>
+#include <optional>
+#include <queue>
#include <string_view>
#include <vector>
@@ -177,6 +179,10 @@
.count();
}
+ std::chrono::nanoseconds channel_storage_duration() const {
+ return channel_storage_duration_;
+ }
+
// The number of extra buffers (beyond the queue) we pretend to have.
int number_scratch_buffers() const {
// We need to start creating messages before we know how many
@@ -220,8 +226,8 @@
}
// Sends the message to all the connected receivers and fetchers. Returns the
- // sent queue index.
- uint32_t Send(std::shared_ptr<SimulatedMessage> message);
+ // sent queue index, or std::nullopt if messages were sent too fast.
+ std::optional<uint32_t> Send(std::shared_ptr<SimulatedMessage> message);
// Unregisters a fetcher.
void UnregisterFetcher(SimulatedFetcher *fetcher);
@@ -334,22 +340,22 @@
size_t size() override { return simulated_channel_->max_size(); }
- bool DoSend(size_t length, monotonic_clock::time_point monotonic_remote_time,
- realtime_clock::time_point realtime_remote_time,
- uint32_t remote_queue_index,
- const UUID &source_boot_uuid) override;
+ Error DoSend(size_t length, monotonic_clock::time_point monotonic_remote_time,
+ realtime_clock::time_point realtime_remote_time,
+ uint32_t remote_queue_index,
+ const UUID &source_boot_uuid) override;
- bool DoSend(const void *msg, size_t size,
- monotonic_clock::time_point monotonic_remote_time,
- realtime_clock::time_point realtime_remote_time,
- uint32_t remote_queue_index,
- const UUID &source_boot_uuid) override;
+ Error DoSend(const void *msg, size_t size,
+ monotonic_clock::time_point monotonic_remote_time,
+ realtime_clock::time_point realtime_remote_time,
+ uint32_t remote_queue_index,
+ const UUID &source_boot_uuid) override;
- bool DoSend(const SharedSpan data,
- aos::monotonic_clock::time_point monotonic_remote_time,
- aos::realtime_clock::time_point realtime_remote_time,
- uint32_t remote_queue_index,
- const UUID &source_boot_uuid) override;
+ Error DoSend(const SharedSpan data,
+ aos::monotonic_clock::time_point monotonic_remote_time,
+ aos::realtime_clock::time_point realtime_remote_time,
+ uint32_t remote_queue_index,
+ const UUID &source_boot_uuid) override;
int buffer_index() override {
// First, ensure message_ is allocated.
@@ -912,10 +918,11 @@
return ::std::move(fetcher);
}
-uint32_t SimulatedChannel::Send(std::shared_ptr<SimulatedMessage> message) {
- const uint32_t queue_index = next_queue_index_.index();
- message->context.queue_index = queue_index;
+std::optional<uint32_t> SimulatedChannel::Send(
+ std::shared_ptr<SimulatedMessage> message) {
+ std::optional<uint32_t> queue_index = {next_queue_index_.index()};
+ message->context.queue_index = *queue_index;
// Points to the actual data depending on the size set in context. Data may
// allocate more than the actual size of the message, so offset from the back
// of that to get the actual start of the data.
@@ -943,7 +950,6 @@
for (auto &fetcher : fetchers_) {
fetcher->Enqueue(message);
}
-
return queue_index;
}
@@ -963,11 +969,10 @@
simulated_channel_->CountSenderDestroyed();
}
-bool SimulatedSender::DoSend(size_t length,
- monotonic_clock::time_point monotonic_remote_time,
- realtime_clock::time_point realtime_remote_time,
- uint32_t remote_queue_index,
- const UUID &source_boot_uuid) {
+RawSender::Error SimulatedSender::DoSend(
+ size_t length, monotonic_clock::time_point monotonic_remote_time,
+ realtime_clock::time_point realtime_remote_time,
+ uint32_t remote_queue_index, const UUID &source_boot_uuid) {
VLOG(1) << simulated_event_loop_->distributed_now() << " "
<< NodeName(simulated_event_loop_->node())
<< simulated_event_loop_->monotonic_now() << " "
@@ -988,8 +993,31 @@
CHECK_LE(length, message_->context.size);
message_->context.size = length;
- // TODO(austin): Track sending too fast.
- sent_queue_index_ = simulated_channel_->Send(message_);
+ const std::optional<uint32_t> optional_queue_index =
+ simulated_channel_->Send(message_);
+
+ // Check that we are not sending messages too fast
+ if (!optional_queue_index) {
+ VLOG(1) << simulated_event_loop_->distributed_now() << " "
+ << NodeName(simulated_event_loop_->node())
+ << simulated_event_loop_->monotonic_now() << " "
+ << simulated_event_loop_->name()
+ << "\nMessages were sent too fast:\n"
+ << "For channel: "
+ << configuration::CleanedChannelToString(
+ simulated_channel_->channel())
+ << '\n'
+ << "Tried to send more than " << simulated_channel_->queue_size()
+ << " (queue size) messages in the last "
+ << std::chrono::duration<double>(
+ simulated_channel_->channel_storage_duration())
+ .count()
+ << " seconds (channel storage duration)"
+ << "\n\n";
+ return Error::kMessagesSentTooFast;
+ }
+
+ sent_queue_index_ = *optional_queue_index;
monotonic_sent_time_ = simulated_event_loop_->monotonic_now();
realtime_sent_time_ = simulated_event_loop_->realtime_now();
@@ -997,14 +1025,14 @@
// next time. Otherwise we will continue to reuse the same memory for all
// messages and corrupt it.
message_.reset();
- return true;
+ return Error::kOk;
}
-bool SimulatedSender::DoSend(const void *msg, size_t size,
- monotonic_clock::time_point monotonic_remote_time,
- realtime_clock::time_point realtime_remote_time,
- uint32_t remote_queue_index,
- const UUID &source_boot_uuid) {
+RawSender::Error SimulatedSender::DoSend(
+ const void *msg, size_t size,
+ monotonic_clock::time_point monotonic_remote_time,
+ realtime_clock::time_point realtime_remote_time,
+ uint32_t remote_queue_index, const UUID &source_boot_uuid) {
CHECK_LE(size, this->size())
<< ": Attempting to send too big a message on "
<< configuration::CleanedChannelToString(simulated_channel_->channel());
@@ -1021,11 +1049,11 @@
remote_queue_index, source_boot_uuid);
}
-bool SimulatedSender::DoSend(const RawSender::SharedSpan data,
- monotonic_clock::time_point monotonic_remote_time,
- realtime_clock::time_point realtime_remote_time,
- uint32_t remote_queue_index,
- const UUID &source_boot_uuid) {
+RawSender::Error SimulatedSender::DoSend(
+ const RawSender::SharedSpan data,
+ monotonic_clock::time_point monotonic_remote_time,
+ realtime_clock::time_point realtime_remote_time,
+ uint32_t remote_queue_index, const UUID &source_boot_uuid) {
CHECK_LE(data->size(), this->size())
<< ": Attempting to send too big a message on "
<< configuration::CleanedChannelToString(simulated_channel_->channel());
diff --git a/aos/events/simulated_event_loop_test.cc b/aos/events/simulated_event_loop_test.cc
index 75e3f85..696c16e 100644
--- a/aos/events/simulated_event_loop_test.cc
+++ b/aos/events/simulated_event_loop_test.cc
@@ -1,5 +1,6 @@
#include "aos/events/simulated_event_loop.h"
+#include <chrono>
#include <string_view>
#include "aos/events/event_loop_param_test.h"
@@ -174,7 +175,8 @@
TestMessage::Builder test_message_builder =
builder.MakeBuilder<TestMessage>();
test_message_builder.add_value(value);
- builder.Send(test_message_builder.Finish());
+ ASSERT_EQ(builder.Send(test_message_builder.Finish()),
+ RawSender::Error::kOk);
}
// Test that sending a message after running gets properly notified.
@@ -337,7 +339,7 @@
aos::Sender<TestMessage>::Builder msg = sender.MakeBuilder();
TestMessage::Builder builder = msg.MakeBuilder<TestMessage>();
builder.add_value(200 + i);
- ASSERT_TRUE(msg.Send(builder.Finish()));
+ msg.CheckOk(msg.Send(builder.Finish()));
}
});
@@ -1394,7 +1396,7 @@
aos::Sender<examples::Ping>::Builder builder = sender->MakeBuilder();
examples::Ping::Builder ping_builder = builder.MakeBuilder<examples::Ping>();
ping_builder.add_value(value);
- builder.Send(ping_builder.Finish());
+ builder.CheckOk(builder.Send(ping_builder.Finish()));
}
// Tests that reliable (and unreliable) ping messages get forwarded as expected.
diff --git a/aos/events/simulated_network_bridge.cc b/aos/events/simulated_network_bridge.cc
index b87182a..96a614d 100644
--- a/aos/events/simulated_network_bridge.cc
+++ b/aos/events/simulated_network_bridge.cc
@@ -61,10 +61,10 @@
timestamp_timer_ =
fetch_event_loop_->AddTimer([this]() { SendTimestamp(); });
if (send_event_loop_) {
- std::string timer_name = absl::StrCat(
- send_event_loop_->node()->name()->string_view(), " ",
- fetcher_->channel()->name()->string_view(), " ",
- fetcher_->channel()->type()->string_view());
+ std::string timer_name =
+ absl::StrCat(send_event_loop_->node()->name()->string_view(), " ",
+ fetcher_->channel()->name()->string_view(), " ",
+ fetcher_->channel()->type()->string_view());
if (timer_) {
timer_->set_name(timer_name);
}
@@ -250,11 +250,11 @@
return;
}
// Fill out the send times.
- sender_->Send(fetcher_->context().data, fetcher_->context().size,
- fetcher_->context().monotonic_event_time,
- fetcher_->context().realtime_event_time,
- fetcher_->context().queue_index,
- fetcher_->context().source_boot_uuid);
+ sender_->CheckOk(sender_->Send(
+ fetcher_->context().data, fetcher_->context().size,
+ fetcher_->context().monotonic_event_time,
+ fetcher_->context().realtime_event_time,
+ fetcher_->context().queue_index, fetcher_->context().source_boot_uuid));
// And simulate message_bridge's offset recovery.
client_status_->SampleFilter(client_index_,
@@ -338,8 +338,8 @@
while (remote_timestamps_.front().monotonic_timestamp_time ==
scheduled_time_) {
if (server_connection_->state() == State::CONNECTED) {
- timestamp_logger_->Send(
- std::move(remote_timestamps_.front().remote_message));
+ timestamp_logger_->CheckOk(timestamp_logger_->Send(
+ std::move(remote_timestamps_.front().remote_message)));
}
remote_timestamps_.pop_front();
if (remote_timestamps_.empty()) {
diff --git a/aos/logging/log_message.fbs b/aos/logging/log_message.fbs
index b68287f..db28a6f 100644
--- a/aos/logging/log_message.fbs
+++ b/aos/logging/log_message.fbs
@@ -22,6 +22,9 @@
// Application name
name:string (id: 3);
+
+ // Total number of LogMessage send failures.
+ send_failures:uint64 (id: 4);
}
root_type LogMessageFbs;
diff --git a/aos/network/message_bridge_client_lib.cc b/aos/network/message_bridge_client_lib.cc
index 2b46dc2..f535c4f 100644
--- a/aos/network/message_bridge_client_lib.cc
+++ b/aos/network/message_bridge_client_lib.cc
@@ -257,13 +257,14 @@
// Publish the message.
RawSender *sender = channel_state->sender.get();
- sender->Send(remote_data->data()->data(), remote_data->data()->size(),
- monotonic_clock::time_point(
- chrono::nanoseconds(remote_data->monotonic_sent_time())),
- realtime_clock::time_point(
- chrono::nanoseconds(remote_data->realtime_sent_time())),
- remote_data->queue_index(),
- UUID::FromVector(remote_data->boot_uuid()));
+ sender->CheckOk(sender->Send(
+ remote_data->data()->data(), remote_data->data()->size(),
+ monotonic_clock::time_point(
+ chrono::nanoseconds(remote_data->monotonic_sent_time())),
+ realtime_clock::time_point(
+ chrono::nanoseconds(remote_data->realtime_sent_time())),
+ remote_data->queue_index(),
+ UUID::FromVector(remote_data->boot_uuid())));
client_status_->SampleFilter(
client_index_,
diff --git a/aos/network/message_bridge_client_status.cc b/aos/network/message_bridge_client_status.cc
index faade70..357026a 100644
--- a/aos/network/message_bridge_client_status.cc
+++ b/aos/network/message_bridge_client_status.cc
@@ -122,7 +122,7 @@
builder.MakeBuilder<ClientStatistics>();
client_statistics_builder.add_connections(client_connections_offset);
- builder.Send(client_statistics_builder.Finish());
+ builder.CheckOk(builder.Send(client_statistics_builder.Finish()));
}
int MessageBridgeClientStatus::FindClientIndex(std::string_view node_name) {
diff --git a/aos/network/message_bridge_server.fbs b/aos/network/message_bridge_server.fbs
index cdf970c..128f1f3 100644
--- a/aos/network/message_bridge_server.fbs
+++ b/aos/network/message_bridge_server.fbs
@@ -40,6 +40,9 @@
// Statistics for all connections to all the clients.
table ServerStatistics {
connections:[ServerConnection] (id: 0);
+
+ // Count of timestamp send failures
+ timestamp_send_failures:uint64 (id: 1);
}
root_type ServerStatistics;
diff --git a/aos/network/message_bridge_server_lib.cc b/aos/network/message_bridge_server_lib.cc
index 006f2b1..41fb915 100644
--- a/aos/network/message_bridge_server_lib.cc
+++ b/aos/network/message_bridge_server_lib.cc
@@ -159,7 +159,7 @@
server_status->AddPartialDeliveries(peer.node_index,
partial_deliveries);
- builder.Send(remote_message_builder.Finish());
+ builder.CheckOk(builder.Send(remote_message_builder.Finish()));
}
break;
}
diff --git a/aos/network/message_bridge_server_status.cc b/aos/network/message_bridge_server_status.cc
index f7553e4..09355b2 100644
--- a/aos/network/message_bridge_server_status.cc
+++ b/aos/network/message_bridge_server_status.cc
@@ -87,7 +87,8 @@
filters_.resize(event_loop->configuration()->nodes()->size());
partial_deliveries_.resize(event_loop->configuration()->nodes()->size());
- boot_uuids_.resize(event_loop->configuration()->nodes()->size(), UUID::Zero());
+ boot_uuids_.resize(event_loop->configuration()->nodes()->size(),
+ UUID::Zero());
has_boot_uuids_.resize(event_loop->configuration()->nodes()->size(), false);
timestamp_fetchers_.resize(event_loop->configuration()->nodes()->size());
server_connection_.resize(event_loop->configuration()->nodes()->size());
@@ -217,7 +218,10 @@
ServerStatistics::Builder server_statistics_builder =
builder.MakeBuilder<ServerStatistics>();
server_statistics_builder.add_connections(server_connections_offset);
- builder.Send(server_statistics_builder.Finish());
+ server_statistics_builder.add_timestamp_send_failures(
+ timestamp_failure_counter_.failures());
+
+ builder.CheckOk(builder.Send(server_statistics_builder.Finish()));
}
void MessageBridgeServerStatus::Tick() {
@@ -352,20 +356,24 @@
// Send it out over shm, and using that timestamp, then send it out over sctp.
// This avoid some context switches.
if (!send_) return;
- timestamp_sender_.Send(timestamp_copy);
- Context context;
- context.monotonic_event_time = timestamp_sender_.monotonic_sent_time();
- context.realtime_event_time = timestamp_sender_.realtime_sent_time();
- context.queue_index = timestamp_sender_.sent_queue_index();
- context.size = timestamp_copy.span().size();
- context.source_boot_uuid = event_loop_->boot_uuid();
- context.data = timestamp_copy.span().data();
+ const auto err = timestamp_sender_.Send(timestamp_copy);
+ timestamp_failure_counter_.Count(err);
+ // Reply only if we successfully sent the timestamp
+ if (err == RawSender::Error::kOk) {
+ Context context;
+ context.monotonic_event_time = timestamp_sender_.monotonic_sent_time();
+ context.realtime_event_time = timestamp_sender_.realtime_sent_time();
+ context.queue_index = timestamp_sender_.sent_queue_index();
+ context.size = timestamp_copy.span().size();
+ context.source_boot_uuid = event_loop_->boot_uuid();
+ context.data = timestamp_copy.span().data();
- // Since we are building up the timestamp to send here, we need to trigger the
- // SendData call ourselves.
- if (send_data_) {
- send_data_(context);
+ // Since we are building up the timestamp to send here, we need to trigger
+ // the SendData call ourselves.
+ if (send_data_) {
+ send_data_(context);
+ }
}
}
diff --git a/aos/network/message_bridge_server_status.h b/aos/network/message_bridge_server_status.h
index c17e00a..3a1c9ed 100644
--- a/aos/network/message_bridge_server_status.h
+++ b/aos/network/message_bridge_server_status.h
@@ -113,6 +113,8 @@
// Sender for the timestamps that we are forwarding over the network.
aos::Sender<Timestamp> timestamp_sender_;
+ SendFailureCounter timestamp_failure_counter_;
+
aos::monotonic_clock::time_point last_statistics_send_time_ =
aos::monotonic_clock::min_time;
@@ -123,7 +125,6 @@
std::vector<uint32_t> partial_deliveries_;
};
-
} // namespace message_bridge
} // namespace aos
diff --git a/aos/network/message_bridge_test.cc b/aos/network/message_bridge_test.cc
index 2a43170..8246c22 100644
--- a/aos/network/message_bridge_test.cc
+++ b/aos/network/message_bridge_test.cc
@@ -450,7 +450,8 @@
examples::Ping::Builder ping_builder =
builder.MakeBuilder<examples::Ping>();
ping_builder.add_value(ping_count + 971);
- builder.Send(ping_builder.Finish());
+ EXPECT_EQ(builder.Send(ping_builder.Finish()),
+ RawSender::Error::kOk);
++ping_count;
}
});
@@ -985,7 +986,7 @@
aos::Sender<examples::Ping>::Builder builder = sender->MakeBuilder();
examples::Ping::Builder ping_builder = builder.MakeBuilder<examples::Ping>();
ping_builder.add_value(value);
- builder.Send(ping_builder.Finish());
+ builder.CheckOk(builder.Send(ping_builder.Finish()));
}
// Tests that when a message is sent before the bridge starts up, but is
@@ -1148,7 +1149,7 @@
examples::Ping::Builder ping_builder =
builder.MakeBuilder<examples::Ping>();
ping_builder.add_value(1);
- builder.Send(ping_builder.Finish());
+ builder.CheckOk(builder.Send(ping_builder.Finish()));
}
MakePi1Client();
diff --git a/aos/network/timestamp_filter.h b/aos/network/timestamp_filter.h
index 0645139..c395554 100644
--- a/aos/network/timestamp_filter.h
+++ b/aos/network/timestamp_filter.h
@@ -344,7 +344,7 @@
return std::nullopt;
}
- size_t current_filter = current_filter_;
+ size_t current_filter = std::max(static_cast<ssize_t>(0), current_filter_);
while (true) {
const BootFilter &filter = filters_[current_filter];
std::optional<
@@ -372,21 +372,23 @@
if (filters_.size() == 0u) {
return std::nullopt;
}
- DCHECK_LT(current_filter_, filters_.size());
+ DCHECK_LT(current_filter_, static_cast<ssize_t>(filters_.size()));
while (true) {
- BootFilter &filter = filters_[current_filter_];
std::optional<
std::tuple<monotonic_clock::time_point, std::chrono::nanoseconds>>
- result = filter.filter.Consume();
+ result =
+ current_filter_ < 0 ? std::nullopt
+ : filters_[current_filter_].filter.Consume();
if (!result) {
- if (current_filter_ + 1 == filters_.size()) {
+ if (static_cast<size_t>(current_filter_ + 1) == filters_.size()) {
return std::nullopt;
} else {
++current_filter_;
continue;
}
}
+ BootFilter &filter = filters_[current_filter_];
return std::make_tuple(
logger::BootTimestamp{static_cast<size_t>(filter.boot.first),
std::get<0>(*result)},
@@ -629,10 +631,10 @@
return &it->filter;
}
- if (!filters_.empty()) {
- CHECK_LT(current_filter_, filters_.size());
+ if (!filters_.empty() && current_filter_ >= 0) {
+ CHECK_LT(static_cast<size_t>(current_filter_), filters_.size());
CHECK_GE(boota, filters_[current_filter_].boot.first);
- CHECK_GE(bootb, filters_[current_filter_].boot.second);
+ CHECK_GE(bootb, filters_[current_filter_].boot.second) << NodeNames();
}
SingleFilter *result =
&filters_
@@ -666,14 +668,15 @@
std::lower_bound(filters_.begin(), filters_.end(),
std::make_pair(boota, bootb), FilterLessThanLower);
CHECK(it != filters_.end());
- CHECK(it->boot == std::make_pair(boota, bootb));
+ CHECK(it->boot == std::make_pair(boota, bootb))
+ << NodeNames() << " Failed to find " << boota << ", " << bootb;
return &it->filter;
}
private:
std::vector<BootFilter> filters_;
- size_t current_filter_ = 0;
+ ssize_t current_filter_ = -1;
// The filter to resume popping from.
size_t pop_filter_ = 0;
diff --git a/aos/network/www/aos_plotter.ts b/aos/network/www/aos_plotter.ts
index 270c0d9..0145c07 100644
--- a/aos/network/www/aos_plotter.ts
+++ b/aos/network/www/aos_plotter.ts
@@ -190,7 +190,6 @@
private plots: AosPlot[] = [];
private messages = new Set<MessageHandler>();
- private lowestHeight = 0;
constructor(private readonly connection: Connection) {
// Set up to redraw at some regular interval. The exact rate is unimportant.
setInterval(() => {
@@ -223,24 +222,19 @@
// Add a new figure at the provided position with the provided size within
// parentElement.
addPlot(
- parentElement: Element, topLeft: number[]|null = null,
+ parentElement: Element,
size: number[] = [AosPlotter.DEFAULT_WIDTH, AosPlotter.DEFAULT_HEIGHT]):
AosPlot {
- if (topLeft === null) {
- topLeft = [0, this.lowestHeight];
- }
const div = document.createElement("div");
- div.style.top = topLeft[1].toString();
- div.style.left = topLeft[0].toString();
- div.style.position = 'absolute';
+ div.style.position = 'relative';
+ div.style.width = size[0].toString() + "px";
+ div.style.height = size[1].toString() + "px";
parentElement.appendChild(div);
- const newPlot = new Plot(div, size[0], size[1]);
+ const newPlot = new Plot(div);
for (let plot of this.plots.values()) {
newPlot.linkXAxis(plot.plot);
}
this.plots.push(new AosPlot(this, newPlot));
- // Height goes up as you go down.
- this.lowestHeight = Math.max(topLeft[1] + size[1], this.lowestHeight);
return this.plots[this.plots.length - 1];
}
private draw(): void {
diff --git a/aos/network/www/colors.ts b/aos/network/www/colors.ts
index b173e13..5c5dd86 100644
--- a/aos/network/www/colors.ts
+++ b/aos/network/www/colors.ts
@@ -1,4 +1,6 @@
export const RED: number[] = [1, 0, 0];
+export const ORANGE: number[] = [1, 0.65, 0];
+export const YELLOW: number[] = [1, 1, 0];
export const GREEN: number[] = [0, 1, 0];
export const BLUE: number[] = [0, 0, 1];
export const BROWN: number[] = [0.6, 0.3, 0];
diff --git a/aos/network/www/demo_plot.ts b/aos/network/www/demo_plot.ts
index cbd133a..ecd4da6 100644
--- a/aos/network/www/demo_plot.ts
+++ b/aos/network/www/demo_plot.ts
@@ -23,12 +23,12 @@
const height = AosPlotter.DEFAULT_HEIGHT;
const benchmarkDiv = document.createElement('div');
- benchmarkDiv.style.top = (height * 2).toString();
- benchmarkDiv.style.left = '0';
- benchmarkDiv.style.position = 'absolute';
+ benchmarkDiv.style.width = width.toString() + "px";
+ benchmarkDiv.style.height = height.toString() + "px";
+ benchmarkDiv.style.position = 'relative';
parentDiv.appendChild(benchmarkDiv);
- const benchmarkPlot = new Plot(benchmarkDiv, width, height);
+ const benchmarkPlot = new Plot(benchmarkDiv);
const aosPlotter = new AosPlotter(conn);
diff --git a/aos/network/www/plotter.ts b/aos/network/www/plotter.ts
index e56a808..842f1b7 100644
--- a/aos/network/www/plotter.ts
+++ b/aos/network/www/plotter.ts
@@ -409,7 +409,7 @@
public static readonly COLOR_CYCLE = [
Colors.RED, Colors.GREEN, Colors.BLUE, Colors.BROWN, Colors.PINK,
- Colors.CYAN, Colors.WHITE
+ Colors.CYAN, Colors.WHITE, Colors.ORANGE, Colors.YELLOW
];
private colorCycleIndex = 0;
@@ -850,6 +850,7 @@
export class Plot {
private canvas = document.createElement('canvas');
private textCanvas = document.createElement('canvas');
+ private lineDrawerContext: WebGLRenderingContext;
private drawer: LineDrawer;
private static keysPressed:
object = {'x': false, 'y': false, 'Escape': false};
@@ -869,25 +870,26 @@
private defaultYRange: number[]|null = null;
private zoomRectangle: Line;
- constructor(wrapperDiv: HTMLDivElement, width: number, height: number) {
+ constructor(wrapperDiv: HTMLDivElement) {
wrapperDiv.appendChild(this.canvas);
wrapperDiv.appendChild(this.textCanvas);
this.lastTimeMs = (new Date()).getTime();
- this.canvas.width =
- width - this.axisLabelBuffer.left - this.axisLabelBuffer.right;
- this.canvas.height =
- height - this.axisLabelBuffer.top - this.axisLabelBuffer.bottom;
- this.canvas.style.left = this.axisLabelBuffer.left.toString();
- this.canvas.style.top = this.axisLabelBuffer.top.toString();
- this.canvas.style.position = 'absolute';
- this.drawer = new LineDrawer(this.canvas.getContext('webgl'));
+ this.canvas.style.paddingLeft = this.axisLabelBuffer.left.toString() + "px";
+ this.canvas.style.paddingRight = this.axisLabelBuffer.right.toString() + "px";
+ this.canvas.style.paddingTop = this.axisLabelBuffer.top.toString() + "px";
+ this.canvas.style.paddingBottom = this.axisLabelBuffer.bottom.toString() + "px";
+ this.canvas.style.width = "100%";
+ this.canvas.style.height = "100%";
+ this.canvas.style.boxSizing = "border-box";
- this.textCanvas.width = width;
- this.textCanvas.height = height;
- this.textCanvas.style.left = '0';
- this.textCanvas.style.top = '0';
+ this.canvas.style.position = 'absolute';
+ this.lineDrawerContext = this.canvas.getContext('webgl');
+ this.drawer = new LineDrawer(this.lineDrawerContext);
+
this.textCanvas.style.position = 'absolute';
+ this.textCanvas.style.width = "100%";
+ this.textCanvas.style.height = "100%";
this.textCanvas.style.pointerEvents = 'none';
this.canvas.addEventListener('dblclick', (e) => {
@@ -934,9 +936,22 @@
}
mouseCanvasLocation(event: MouseEvent): number[] {
+ const computedStyle = window.getComputedStyle(this.canvas);
+ const paddingLeftStr = computedStyle.getPropertyValue('padding-left');
+ const paddingTopStr = computedStyle.getPropertyValue('padding-top');
+ if (paddingLeftStr.substring(paddingLeftStr.length - 2) != "px") {
+ throw new Error("Left padding should be specified in pixels.");
+ }
+ if (paddingTopStr.substring(paddingTopStr.length - 2) != "px") {
+ throw new Error("Left padding should be specified in pixels.");
+ }
+ // Javascript will just ignore the extra "px".
+ const paddingLeft = Number.parseInt(paddingLeftStr);
+ const paddingTop = Number.parseInt(paddingTopStr);
+
return [
- event.offsetX * 2.0 / this.canvas.width - 1.0,
- -event.offsetY * 2.0 / this.canvas.height + 1.0
+ (event.offsetX - paddingLeft) * 2.0 / this.canvas.width - 1.0,
+ -(event.offsetY - paddingTop) * 2.0 / this.canvas.height + 1.0
];
}
@@ -1154,6 +1169,17 @@
const curTime = (new Date()).getTime();
const frameRate = 1000.0 / (curTime - this.lastTimeMs);
this.lastTimeMs = curTime;
+ const parentWidth = this.textCanvas.parentElement.offsetWidth;
+ const parentHeight = this.textCanvas.parentElement.offsetHeight;
+ this.textCanvas.width = parentWidth;
+ this.textCanvas.height = parentHeight;
+ this.canvas.width =
+ parentWidth - this.axisLabelBuffer.left - this.axisLabelBuffer.right;
+ this.canvas.height =
+ parentHeight - this.axisLabelBuffer.top - this.axisLabelBuffer.bottom;
+ this.lineDrawerContext.viewport(
+ 0, 0, this.lineDrawerContext.drawingBufferWidth,
+ this.lineDrawerContext.drawingBufferHeight);
// Clear the overlay.
const textCtx = this.textCanvas.getContext("2d");
diff --git a/aos/starter/starter_rpc_lib.cc b/aos/starter/starter_rpc_lib.cc
index b0b9db3..3007326 100644
--- a/aos/starter/starter_rpc_lib.cc
+++ b/aos/starter/starter_rpc_lib.cc
@@ -3,6 +3,7 @@
#include "aos/events/shm_event_loop.h"
#include "aos/flatbuffer_merge.h"
#include "aos/starter/starterd_lib.h"
+#include "glog/logging.h"
namespace aos {
namespace starter {
@@ -163,7 +164,7 @@
if (is_multi_node) {
command_builder.add_nodes(nodes_offset);
}
- CHECK(builder.Send(command_builder.Finish()));
+ builder.CheckOk(builder.Send(command_builder.Finish()));
}
timeout_timer_->Setup(event_loop_->monotonic_now() + timeout);
diff --git a/aos/starter/starterd_lib.cc b/aos/starter/starterd_lib.cc
index bc83768..7bf2e0d 100644
--- a/aos/starter/starterd_lib.cc
+++ b/aos/starter/starterd_lib.cc
@@ -602,7 +602,7 @@
aos::starter::Status::Builder status_builder(*builder.fbb());
status_builder.add_statuses(statuses_fbs);
- CHECK(builder.Send(status_builder.Finish()));
+ builder.CheckOk(builder.Send(status_builder.Finish()));
}
} // namespace starter
diff --git a/build_tests/BUILD b/build_tests/BUILD
index 0766256..d142c13 100644
--- a/build_tests/BUILD
+++ b/build_tests/BUILD
@@ -85,8 +85,6 @@
name = "python3_opencv",
srcs = ["python_opencv.py"],
main = "python_opencv.py",
- python_version = "PY3",
- srcs_version = "PY2AND3",
target_compatible_with = ["@platforms//os:linux"],
deps = ["@opencv_contrib_nonfree_amd64//:python_opencv"],
)
diff --git a/debian/BUILD b/debian/BUILD
index 348163e..0ea9836 100644
--- a/debian/BUILD
+++ b/debian/BUILD
@@ -116,8 +116,6 @@
"download_packages.py",
],
main = "download_packages.py",
- python_version = "PY3",
- srcs_version = "PY2AND3",
target_compatible_with = ["@platforms//os:linux"],
)
diff --git a/debian/opencv_python.BUILD b/debian/opencv_python.BUILD
index 5afa180..5074bd3 100644
--- a/debian/opencv_python.BUILD
+++ b/debian/opencv_python.BUILD
@@ -5,6 +5,9 @@
include = ["**/*"],
exclude = ["**/*.py"],
),
+ deps = [
+ "@python_repo//:numpy",
+ ],
imports = ["."],
visibility = ["//visibility:public"],
)
diff --git a/debian/python.BUILD b/debian/python.BUILD
index 17543df..009a7e2 100644
--- a/debian/python.BUILD
+++ b/debian/python.BUILD
@@ -55,11 +55,45 @@
visibility = ["//visibility:public"],
)
-filegroup(
+py_library(
name = "scipy",
srcs = glob([
- "usr/lib/python3/dist-packages/numpy",
- "usr/lib/python3/dist-packages/scipy",
+ "usr/lib/python3/dist-packages/scipy/**/*.py",
+ ]),
+ data = glob([
+ "usr/lib/python3/dist-packages/scipy/**/*",
+ ], exclude = [
+ "usr/lib/python3/dist-packages/scipy/**/*.py",
+ ]),
+ deps = [
+ ":numpy",
+ ],
+ visibility = ["//visibility:public"],
+ imports = [
+ "usr/lib/python3/dist-packages",
+ ],
+ target_compatible_with = [
+ "@platforms//os:linux",
+ "@platforms//cpu:x86_64",
+ ],
+)
+
+py_library(
+ name = "numpy",
+ srcs = glob([
+ "usr/lib/python3/dist-packages/numpy/**/*.py",
+ ]),
+ data = glob([
+ "usr/lib/python3/dist-packages/numpy/**/*",
+ ], exclude = [
+ "usr/lib/python3/dist-packages/numpy/**/*.py",
]),
visibility = ["//visibility:public"],
+ imports = [
+ "usr/lib/python3/dist-packages",
+ ],
+ target_compatible_with = [
+ "@platforms//os:linux",
+ "@platforms//cpu:x86_64",
+ ],
)
diff --git a/frc971/analysis/BUILD b/frc971/analysis/BUILD
index 5457405..4850f97 100644
--- a/frc971/analysis/BUILD
+++ b/frc971/analysis/BUILD
@@ -52,6 +52,7 @@
"//y2020/control_loops/superstructure:finisher_plotter",
"//y2020/control_loops/superstructure:hood_plotter",
"//y2020/control_loops/superstructure:turret_plotter",
+ "//y2021_bot3/control_loops/superstructure:superstructure_plotter",
],
)
diff --git a/frc971/analysis/in_process_plotter.cc b/frc971/analysis/in_process_plotter.cc
index e82cb2f..0eaf719 100644
--- a/frc971/analysis/in_process_plotter.cc
+++ b/frc971/analysis/in_process_plotter.cc
@@ -25,6 +25,9 @@
color_wheel_.push_back(Color(1, 1, 0));
color_wheel_.push_back(Color(0, 1, 1));
color_wheel_.push_back(Color(1, 0, 1));
+ color_wheel_.push_back(Color(1, 0.6, 0));
+ color_wheel_.push_back(Color(0.6, 0.3, 0));
+ color_wheel_.push_back(Color(1, 1, 1));
}
void Plotter::Spin() { event_loop_factory_.Run(); }
@@ -74,8 +77,8 @@
for (size_t ii = 0; ii < x.size(); ++ii) {
points.emplace_back(x[ii], y[ii]);
}
- const flatbuffers::Offset<flatbuffers::Vector<const Point*>>
- points_offset = builder_.fbb()->CreateVectorOfStructs(points);
+ const flatbuffers::Offset<flatbuffers::Vector<const Point *>> points_offset =
+ builder_.fbb()->CreateVectorOfStructs(points);
const Color *color = &color_wheel_.at(color_wheel_position_);
color_wheel_position_ = (color_wheel_position_ + 1) % color_wheel_.size();
@@ -118,7 +121,8 @@
plot_builder.add_title(title_);
plot_builder.add_figures(figures_offset);
- builder_.Send(plot_builder.Finish());
+ CHECK_EQ(builder_.Send(plot_builder.Finish()),
+ aos::RawSender::Error::kOk);
builder_ = plot_sender_.MakeBuilder();
diff --git a/frc971/analysis/plot_data_utils.ts b/frc971/analysis/plot_data_utils.ts
index def34ed..5d1f4a0 100644
--- a/frc971/analysis/plot_data_utils.ts
+++ b/frc971/analysis/plot_data_utils.ts
@@ -29,9 +29,6 @@
plotSelect.add(new Option('Select Plot', invalidSelectValue));
const plotDiv = document.createElement('div');
- plotDiv.style.position = 'absolute';
- plotDiv.style.top = '30';
- plotDiv.style.left = '0';
parentDiv.appendChild(plotDiv);
conn.addReliableHandler(
@@ -50,12 +47,11 @@
for (let ii = 0; ii < plotFb.figuresLength(); ++ii) {
const figure = plotFb.figures(ii);
const figureDiv = document.createElement('div');
- figureDiv.style.top = figure.position().top().toString();
- figureDiv.style.left = figure.position().left().toString();
- figureDiv.style.position = 'absolute';
+ figureDiv.style.width = figure.position().width().toString() + "px";
+ figureDiv.style.height = figure.position().height().toString() + "px";
+ figureDiv.style.position = 'relative';
div.appendChild(figureDiv);
- const plot = new Plot(
- figureDiv, figure.position().width(), figure.position().height());
+ const plot = new Plot(figureDiv);
if (figure.title()) {
plot.getAxisLabels().setTitle(figure.title());
diff --git a/frc971/analysis/plot_index.ts b/frc971/analysis/plot_index.ts
index 7b46a70..2df65f6 100644
--- a/frc971/analysis/plot_index.ts
+++ b/frc971/analysis/plot_index.ts
@@ -38,6 +38,8 @@
'org_frc971/y2020/control_loops/superstructure/accelerator_plotter'
import {plotHood} from
'org_frc971/y2020/control_loops/superstructure/hood_plotter'
+import {plotSuperstructure} from
+ 'org_frc971/y2021_bot3/control_loops/superstructure/superstructure_plotter';
import {plotDemo} from 'org_frc971/aos/network/www/demo_plot';
import {plotData} from 'org_frc971/frc971/analysis/plot_data_utils';
@@ -104,6 +106,7 @@
['Turret', new PlotState(plotDiv, plotTurret)],
['2020 Localizer', new PlotState(plotDiv, plotLocalizer)],
['C++ Plotter', new PlotState(plotDiv, plotData)],
+ ['Y2021 3rd Robot Superstructure', new PlotState(plotDiv, plotSuperstructure)],
]);
const invalidSelectValue = 'null';
@@ -151,4 +154,4 @@
plotSelect.value = getDefaultPlot();
// Force the event to occur once at the start.
plotSelect.dispatchEvent(new Event('input'));
-});
+});
\ No newline at end of file
diff --git a/frc971/autonomous/base_autonomous_actor.cc b/frc971/autonomous/base_autonomous_actor.cc
index ab31e52..57aa578 100644
--- a/frc971/autonomous/base_autonomous_actor.cc
+++ b/frc971/autonomous/base_autonomous_actor.cc
@@ -53,7 +53,7 @@
goal_builder.add_highgear(true);
goal_builder.add_wheel(0.0);
goal_builder.add_throttle(throttle);
- builder.Send(goal_builder.Finish());
+ builder.CheckOk(builder.Send(goal_builder.Finish()));
}
void BaseAutonomousActor::ResetDrivetrain() {
@@ -72,7 +72,7 @@
goal_builder.add_left_goal(initial_drivetrain_.left);
goal_builder.add_right_goal(initial_drivetrain_.right);
goal_builder.add_max_ss_voltage(max_drivetrain_voltage_);
- builder.Send(goal_builder.Finish());
+ builder.CheckOk(builder.Send(goal_builder.Finish()));
}
void BaseAutonomousActor::InitializeEncoders() {
@@ -113,7 +113,7 @@
goal_builder.add_linear(linear_offset);
goal_builder.add_angular(angular_offset);
- builder.Send(goal_builder.Finish());
+ builder.CheckOk(builder.Send(goal_builder.Finish()));
}
void BaseAutonomousActor::WaitUntilDoneOrCanceled(
@@ -453,7 +453,7 @@
// line_follow_drivetrain.cc, but it is somewhat year-specific, so we should
// factor it out in some way.
goal_builder.add_throttle(velocity / 4.0);
- builder.Send(goal_builder.Finish());
+ builder.CheckOk(builder.Send(goal_builder.Finish()));
}
{
@@ -463,7 +463,7 @@
::y2019::control_loops::drivetrain::TargetSelectorHint>();
target_hint_builder.add_suggested_target(hint);
- builder.Send(target_hint_builder.Finish());
+ builder.CheckOk(builder.Send(target_hint_builder.Finish()));
}
}
@@ -512,7 +512,7 @@
}
}
- builder.Send(spline_builder.Finish());
+ builder.CheckOk(builder.Send(spline_builder.Finish()));
return BaseAutonomousActor::SplineHandle(spline_handle, this, start);
}
@@ -566,7 +566,7 @@
goal_builder.add_spline_handle(spline_handle_);
base_autonomous_actor_->goal_spline_handle_ = spline_handle_;
- builder.Send(goal_builder.Finish());
+ builder.CheckOk(builder.Send(goal_builder.Finish()));
}
bool BaseAutonomousActor::SplineHandle::IsDone() {
diff --git a/frc971/codelab/basic.cc b/frc971/codelab/basic.cc
index 0393508..325db73 100644
--- a/frc971/codelab/basic.cc
+++ b/frc971/codelab/basic.cc
@@ -29,7 +29,8 @@
// tests pass.
builder.add_intake_voltage(0.0);
- output->Send(builder.Finish());
+ // Ignore the return value of Send
+ (void)output->Send(builder.Finish());
}
if (status) {
@@ -40,7 +41,8 @@
// Look at the definition of Status in basic_status.fbs to find
// the name of the field.
- status->Send(builder.Finish());
+ // Ignore the return value of Send
+ (void)status->Send(builder.Finish());
}
}
diff --git a/frc971/codelab/basic_test.cc b/frc971/codelab/basic_test.cc
index 46226be..dc80988 100644
--- a/frc971/codelab/basic_test.cc
+++ b/frc971/codelab/basic_test.cc
@@ -53,7 +53,8 @@
position_builder.add_limit_sensor(limit_sensor_);
- builder.Send(position_builder.Finish());
+ EXPECT_EQ(builder.Send(position_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
// This is a helper function that is used in the tests to check
@@ -122,7 +123,8 @@
auto builder = goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_intake(true);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
basic_simulation_.set_limit_sensor(false);
@@ -135,7 +137,8 @@
auto builder = goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_intake(true);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
basic_simulation_.set_limit_sensor(true);
@@ -151,7 +154,8 @@
auto builder = goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_intake(true);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
basic_simulation_.set_limit_sensor(false);
@@ -167,7 +171,8 @@
auto builder = goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_intake(false);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
basic_simulation_.set_limit_sensor(false);
@@ -183,7 +188,8 @@
auto builder = goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_intake(true);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
basic_simulation_.set_limit_sensor(true);
@@ -198,7 +204,8 @@
auto builder = goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_intake(false);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
basic_simulation_.set_limit_sensor(true);
@@ -227,7 +234,8 @@
auto builder = goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_intake(true);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
SetEnabled(false);
diff --git a/frc971/control_loops/control_loop-tmpl.h b/frc971/control_loops/control_loop-tmpl.h
index 0db1786..7e20227 100644
--- a/frc971/control_loops/control_loop-tmpl.h
+++ b/frc971/control_loops/control_loop-tmpl.h
@@ -23,7 +23,7 @@
OutputType>::ZeroOutputs() {
typename ::aos::Sender<OutputType>::Builder builder =
output_sender_.MakeBuilder();
- builder.Send(Zero(&builder));
+ builder.CheckOk(builder.Send(Zero(&builder)));
}
template <class GoalType, class PositionType, class StatusType,
diff --git a/frc971/control_loops/control_loop_test.h b/frc971/control_loops/control_loop_test.h
index de9d4cd..a820215 100644
--- a/frc971/control_loops/control_loop_test.h
+++ b/frc971/control_loops/control_loop_test.h
@@ -11,6 +11,7 @@
#include "aos/time/time.h"
#include "frc971/input/joystick_state_generated.h"
#include "frc971/input/robot_state_generated.h"
+#include "glog/logging.h"
#include "gtest/gtest.h"
namespace frc971 {
@@ -123,7 +124,8 @@
builder.add_autonomous(false);
builder.add_team_id(team_id_);
- new_state.Send(builder.Finish());
+ CHECK_EQ(new_state.Send(builder.Finish()),
+ aos::RawSender::Error::kOk);
last_ds_time_ = monotonic_now();
last_enabled_ = enabled_;
@@ -150,7 +152,7 @@
builder.add_voltage_roborio_in(battery_voltage_);
builder.add_voltage_battery(battery_voltage_);
- new_state.Send(builder.Finish());
+ new_state.CheckOk(new_state.Send(builder.Finish()));
}
static constexpr ::std::chrono::microseconds kTimeTick{5000};
diff --git a/frc971/control_loops/drivetrain/down_estimator_plotter.ts b/frc971/control_loops/drivetrain/down_estimator_plotter.ts
index c6e414c..7f5bd58 100644
--- a/frc971/control_loops/drivetrain/down_estimator_plotter.ts
+++ b/frc971/control_loops/drivetrain/down_estimator_plotter.ts
@@ -18,7 +18,7 @@
'/drivetrain', 'frc971.IMUValuesBatch',
new ImuMessageHandler(conn.getSchema('frc971.IMUValuesBatch')));
- const accelPlot = aosPlotter.addPlot(element, [0, 0], [width, height]);
+ const accelPlot = aosPlotter.addPlot(element, [width, height]);
accelPlot.plot.getAxisLabels().setTitle(
'Estimated Accelerations (x = forward, y = lateral, z = vertical)');
accelPlot.plot.getAxisLabels().setYLabel('Acceleration (m/s/s)');
@@ -31,7 +31,7 @@
const accelZ = accelPlot.addMessageLine(status, ['down_estimator', 'accel_z']);
accelZ.setColor(BLUE);
- const velPlot = aosPlotter.addPlot(element, [0, height], [width, height]);
+ const velPlot = aosPlotter.addPlot(element, [width, height]);
velPlot.plot.getAxisLabels().setTitle('Raw IMU Integrated Velocity');
velPlot.plot.getAxisLabels().setYLabel('Velocity (m/s)');
velPlot.plot.getAxisLabels().setXLabel('Monotonic Reading Time (sec)');
@@ -43,7 +43,7 @@
const velZ = velPlot.addMessageLine(status, ['down_estimator', 'velocity_z']);
velZ.setColor(BLUE);
- const gravityPlot = aosPlotter.addPlot(element, [0, height * 2], [width, height]);
+ const gravityPlot = aosPlotter.addPlot(element, [width, height]);
gravityPlot.plot.getAxisLabels().setTitle('Accelerometer Magnitudes');
gravityPlot.plot.getAxisLabels().setXLabel('Monotonic Sent Time (sec)');
gravityPlot.plot.setDefaultYRange([0.95, 1.05]);
@@ -58,7 +58,7 @@
accelMagnitudeLine.setDrawLine(false);
const orientationPlot =
- aosPlotter.addPlot(element, [0, height * 3], [width, height]);
+ aosPlotter.addPlot(element, [width, height]);
orientationPlot.plot.getAxisLabels().setTitle('Orientation');
orientationPlot.plot.getAxisLabels().setYLabel('Angle (rad)');
@@ -75,7 +75,7 @@
yaw.setColor(BLUE);
yaw.setLabel('yaw');
- const imuAccelPlot = aosPlotter.addPlot(element, [0, height * 4], [width, height]);
+ const imuAccelPlot = aosPlotter.addPlot(element, [width, height]);
imuAccelPlot.plot.getAxisLabels().setTitle('Filtered Accelerometer Readings');
imuAccelPlot.plot.getAxisLabels().setYLabel('Acceleration (g)');
imuAccelPlot.plot.getAxisLabels().setXLabel('Monotonic Reading Time (sec)');
@@ -113,7 +113,7 @@
expectedAccelZ.setColor(BLUE);
expectedAccelZ.setPointSize(0);
- const gyroPlot = aosPlotter.addPlot(element, [0, height * 5], [width, height]);
+ const gyroPlot = aosPlotter.addPlot(element, [width, height]);
gyroPlot.plot.getAxisLabels().setTitle('Gyro Readings');
gyroPlot.plot.getAxisLabels().setYLabel('Angular Velocity (rad / sec)');
gyroPlot.plot.getAxisLabels().setXLabel('Monotonic Reading Time (sec)');
@@ -141,7 +141,7 @@
const gyroZ = gyroPlot.addMessageLine(imu, ['gyro_z']);
gyroZ.setColor(BLUE);
- const statePlot = aosPlotter.addPlot(element, [0, height * 6], [width, height / 2]);
+ const statePlot = aosPlotter.addPlot(element, [width, height / 2]);
statePlot.plot.getAxisLabels().setTitle('IMU State');
statePlot.plot.getAxisLabels().setXLabel('Monotonic Sent Time (sec)');
diff --git a/frc971/control_loops/drivetrain/drivetrain.cc b/frc971/control_loops/drivetrain/drivetrain.cc
index 928d418..62b77c4 100644
--- a/frc971/control_loops/drivetrain/drivetrain.cc
+++ b/frc971/control_loops/drivetrain/drivetrain.cc
@@ -526,7 +526,10 @@
builder.add_down_estimator(down_estimator_state_offset);
builder.add_localizer(localizer_offset);
builder.add_zeroing(zeroer_offset);
- status->Send(builder.Finish());
+
+ builder.add_send_failures(status_failure_counter_.failures());
+
+ status_failure_counter_.Count(status->Send(builder.Finish()));
}
// If the filters aren't ready/valid, then disable all outputs (currently,
@@ -568,7 +571,7 @@
}
if (output) {
- output->Send(Output::Pack(*output->fbb(), &output_struct));
+ output->CheckOk(output->Send(Output::Pack(*output->fbb(), &output_struct)));
}
}
diff --git a/frc971/control_loops/drivetrain/drivetrain.h b/frc971/control_loops/drivetrain/drivetrain.h
index efaf53d..52ae605 100644
--- a/frc971/control_loops/drivetrain/drivetrain.h
+++ b/frc971/control_loops/drivetrain/drivetrain.h
@@ -2,9 +2,8 @@
#define FRC971_CONTROL_LOOPS_DRIVETRAIN_H_
#include "Eigen/Dense"
-#include "frc971/control_loops/control_loop.h"
-#include "frc971/control_loops/polytope.h"
#include "aos/util/log_interval.h"
+#include "frc971/control_loops/control_loop.h"
#include "frc971/control_loops/control_loops_generated.h"
#include "frc971/control_loops/drivetrain/drivetrain_config.h"
#include "frc971/control_loops/drivetrain/drivetrain_goal_generated.h"
@@ -20,6 +19,7 @@
#include "frc971/control_loops/drivetrain/polydrivetrain.h"
#include "frc971/control_loops/drivetrain/splinedrivetrain.h"
#include "frc971/control_loops/drivetrain/ssdrivetrain.h"
+#include "frc971/control_loops/polytope.h"
#include "frc971/queues/gyro_generated.h"
#include "frc971/wpilib/imu_batch_generated.h"
#include "frc971/zeroing/imu_zeroer.h"
@@ -185,6 +185,8 @@
LineFollowDrivetrain dt_line_follow_;
bool has_been_enabled_ = false;
+
+ aos::SendFailureCounter status_failure_counter_;
};
} // namespace drivetrain
diff --git a/frc971/control_loops/drivetrain/drivetrain_lib_test.cc b/frc971/control_loops/drivetrain/drivetrain_lib_test.cc
index d658e21..3ad4776 100644
--- a/frc971/control_loops/drivetrain/drivetrain_lib_test.cc
+++ b/frc971/control_loops/drivetrain/drivetrain_lib_test.cc
@@ -183,7 +183,8 @@
goal_builder.add_controller_type(ControllerType::MOTION_PROFILE);
goal_builder.add_left_goal(-1.0);
goal_builder.add_right_goal(1.0);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(2));
VerifyNearGoal();
@@ -199,7 +200,8 @@
goal_builder.add_controller_type(ControllerType::MOTION_PROFILE);
goal_builder.add_left_goal(-1.0);
goal_builder.add_right_goal(1.0);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
// Sanity check that the drivetrain is indeed commanding voltage while the IMU
@@ -235,7 +237,8 @@
goal_builder.add_controller_type(ControllerType::MOTION_PROFILE);
goal_builder.add_left_goal(-1.0);
goal_builder.add_right_goal(1.0);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
drivetrain_plant_.set_left_voltage_offset(1.0);
drivetrain_plant_.set_right_voltage_offset(1.0);
@@ -251,7 +254,8 @@
goal_builder.add_controller_type(ControllerType::MOTION_PROFILE);
goal_builder.add_left_goal(-1.0);
goal_builder.add_right_goal(1.0);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
for (int i = 0; i < 500; ++i) {
if (i > 20 && i < 200) {
@@ -281,7 +285,8 @@
goal_builder.add_controller_type(ControllerType::MOTION_PROFILE);
goal_builder.add_left_goal(4.0);
goal_builder.add_right_goal(4.0);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
for (int i = 0; i < 500; ++i) {
@@ -305,7 +310,8 @@
goal_builder.add_controller_type(ControllerType::MOTION_PROFILE);
goal_builder.add_left_goal(4.0);
goal_builder.add_right_goal(3.9);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
for (int i = 0; i < 500; ++i) {
RunFor(dt());
@@ -366,7 +372,8 @@
goal_builder.add_right_goal(4.0);
goal_builder.add_linear(linear_offset);
goal_builder.add_angular(angular_offset);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
const auto start_time = monotonic_now();
@@ -408,7 +415,8 @@
goal_builder.add_right_goal(1.0);
goal_builder.add_linear(linear_offset);
goal_builder.add_angular(angular_offset);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
const auto start_time = monotonic_now();
@@ -450,7 +458,8 @@
goal_builder.add_right_goal(4.0);
goal_builder.add_linear(linear_offset);
goal_builder.add_angular(angular_offset);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
const auto start_time = monotonic_now();
@@ -473,7 +482,8 @@
goal_builder.add_throttle(1.0);
goal_builder.add_highgear(true);
goal_builder.add_quickturn(false);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(1));
@@ -486,7 +496,8 @@
goal_builder.add_throttle(-0.3);
goal_builder.add_highgear(true);
goal_builder.add_quickturn(false);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(1));
@@ -499,7 +510,8 @@
goal_builder.add_throttle(0.0);
goal_builder.add_highgear(true);
goal_builder.add_quickturn(false);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(10));
@@ -526,7 +538,8 @@
goal_builder.add_right_goal(4.0);
goal_builder.add_linear(linear_offset);
goal_builder.add_angular(angular_offset);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
const auto end_time = monotonic_now() + chrono::seconds(4);
@@ -566,7 +579,8 @@
spline_goal_builder.add_spline_idx(1);
spline_goal_builder.add_drive_spline_backwards(false);
spline_goal_builder.add_spline(multispline_offset);
- EXPECT_TRUE(builder.Send(spline_goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(spline_goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(dt());
@@ -576,7 +590,8 @@
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_controller_type(ControllerType::SPLINE_FOLLOWER);
goal_builder.add_spline_handle(1);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::milliseconds(2000));
@@ -611,7 +626,8 @@
spline_goal_builder.add_drive_spline_backwards(true);
spline_goal_builder.add_spline(multispline_offset);
- EXPECT_TRUE(builder.Send(spline_goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(spline_goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(dt());
@@ -620,7 +636,8 @@
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_controller_type(ControllerType::SPLINE_FOLLOWER);
goal_builder.add_spline_handle(1);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
// Check that we are right on the spline at the start (otherwise the feedback
@@ -669,7 +686,8 @@
spline_goal_builder.add_spline_idx(1);
spline_goal_builder.add_drive_spline_backwards(false);
spline_goal_builder.add_spline(multispline_offset);
- EXPECT_TRUE(builder.Send(spline_goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(spline_goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
{
@@ -677,7 +695,8 @@
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_controller_type(ControllerType::SPLINE_FOLLOWER);
goal_builder.add_spline_handle(1);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::milliseconds(2000));
@@ -709,14 +728,16 @@
spline_goal_builder.add_spline_idx(1);
spline_goal_builder.add_drive_spline_backwards(false);
spline_goal_builder.add_spline(multispline_offset);
- ASSERT_TRUE(builder.Send(spline_goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(spline_goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
{
auto builder = drivetrain_goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_controller_type(ControllerType::SPLINE_FOLLOWER);
goal_builder.add_spline_handle(1);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::milliseconds(500));
@@ -728,7 +749,8 @@
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_controller_type(ControllerType::SPLINE_FOLLOWER);
goal_builder.add_spline_handle(0);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
for (int i = 0; i < 100; ++i) {
RunFor(dt());
@@ -769,7 +791,8 @@
spline_goal_builder.add_spline_idx(1);
spline_goal_builder.add_drive_spline_backwards(false);
spline_goal_builder.add_spline(multispline_offset);
- ASSERT_TRUE(builder.Send(spline_goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(spline_goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
{
auto builder = drivetrain_goal_sender_.MakeBuilder();
@@ -777,7 +800,8 @@
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_controller_type(ControllerType::SPLINE_FOLLOWER);
goal_builder.add_spline_handle(1);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::milliseconds(500));
@@ -789,7 +813,8 @@
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_controller_type(ControllerType::SPLINE_FOLLOWER);
goal_builder.add_spline_handle(0);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::milliseconds(500));
@@ -799,7 +824,8 @@
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_controller_type(ControllerType::SPLINE_FOLLOWER);
goal_builder.add_spline_handle(1);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::milliseconds(2000));
@@ -828,7 +854,8 @@
localizer_control_builder.add_x(drivetrain_plant_.state()(0));
localizer_control_builder.add_y(drivetrain_plant_.state()(1));
localizer_control_builder.add_theta(drivetrain_plant_.state()(2));
- ASSERT_TRUE(builder.Send(localizer_control_builder.Finish()));
+ ASSERT_EQ(builder.Send(localizer_control_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
{
auto builder = trajectory_goal_sender_.MakeBuilder();
@@ -852,7 +879,8 @@
spline_goal_builder.add_spline_idx(1);
spline_goal_builder.add_drive_spline_backwards(GetParam());
spline_goal_builder.add_spline(multispline_offset);
- ASSERT_TRUE(builder.Send(spline_goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(spline_goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(dt());
@@ -861,7 +889,8 @@
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_controller_type(ControllerType::SPLINE_FOLLOWER);
goal_builder.add_spline_handle(1);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::milliseconds(5000));
@@ -898,7 +927,8 @@
spline_goal_builder.add_spline_idx(1);
spline_goal_builder.add_drive_spline_backwards(false);
spline_goal_builder.add_spline(multispline_offset);
- ASSERT_TRUE(builder.Send(spline_goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(spline_goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(dt());
@@ -907,7 +937,8 @@
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_controller_type(ControllerType::SPLINE_FOLLOWER);
goal_builder.add_spline_handle(1);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::milliseconds(5000));
@@ -947,7 +978,8 @@
spline_goal_builder.add_spline_idx(1);
spline_goal_builder.add_drive_spline_backwards(false);
spline_goal_builder.add_spline(multispline_offset);
- ASSERT_TRUE(builder.Send(spline_goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(spline_goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(dt());
@@ -956,7 +988,8 @@
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_controller_type(ControllerType::SPLINE_FOLLOWER);
goal_builder.add_spline_handle(1);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::milliseconds(5000));
@@ -1006,7 +1039,8 @@
spline_goal_builder.add_spline_idx(1);
spline_goal_builder.add_drive_spline_backwards(false);
spline_goal_builder.add_spline(multispline_offset);
- ASSERT_TRUE(builder.Send(spline_goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(spline_goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(dt());
@@ -1015,7 +1049,8 @@
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_controller_type(ControllerType::SPLINE_FOLLOWER);
goal_builder.add_spline_handle(1);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::milliseconds(4000));
@@ -1047,7 +1082,8 @@
spline_goal_builder.add_spline_idx(1);
spline_goal_builder.add_drive_spline_backwards(false);
spline_goal_builder.add_spline(multispline_offset);
- ASSERT_TRUE(builder.Send(spline_goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(spline_goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(dt());
@@ -1056,7 +1092,8 @@
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_controller_type(ControllerType::SPLINE_FOLLOWER);
goal_builder.add_spline_handle(1);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
WaitForTrajectoryExecution();
@@ -1086,7 +1123,8 @@
spline_goal_builder.add_spline_idx(2);
spline_goal_builder.add_drive_spline_backwards(false);
spline_goal_builder.add_spline(multispline_offset);
- ASSERT_TRUE(builder.Send(spline_goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(spline_goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(dt());
@@ -1096,7 +1134,8 @@
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_controller_type(ControllerType::SPLINE_FOLLOWER);
goal_builder.add_spline_handle(2);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::milliseconds(2000));
@@ -1128,14 +1167,16 @@
spline_goal_builder.add_spline_idx(1);
spline_goal_builder.add_drive_spline_backwards(false);
spline_goal_builder.add_spline(multispline_offset);
- ASSERT_TRUE(builder.Send(spline_goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(spline_goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
{
auto builder = drivetrain_goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_controller_type(ControllerType::SPLINE_FOLLOWER);
goal_builder.add_spline_handle(1);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::milliseconds(2000));
@@ -1153,7 +1194,8 @@
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_controller_type(ControllerType::SPLINE_FOLLOWER);
goal_builder.add_spline_handle(0);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::milliseconds(500));
@@ -1180,14 +1222,16 @@
spline_goal_builder.add_spline_idx(2);
spline_goal_builder.add_drive_spline_backwards(false);
spline_goal_builder.add_spline(multispline_offset);
- ASSERT_TRUE(builder.Send(spline_goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(spline_goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
{
auto builder = drivetrain_goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_controller_type(ControllerType::SPLINE_FOLLOWER);
goal_builder.add_spline_handle(2);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
WaitForTrajectoryExecution();
@@ -1222,7 +1266,8 @@
spline_goal_builder.add_spline_idx(1);
spline_goal_builder.add_drive_spline_backwards(false);
spline_goal_builder.add_spline(multispline_offset);
- ASSERT_TRUE(builder.Send(spline_goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(spline_goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::milliseconds(1000));
@@ -1250,7 +1295,8 @@
spline_goal_builder.add_spline_idx(2);
spline_goal_builder.add_drive_spline_backwards(false);
spline_goal_builder.add_spline(multispline_offset);
- ASSERT_TRUE(builder.Send(spline_goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(spline_goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
// Now execute it.
@@ -1259,7 +1305,8 @@
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_controller_type(ControllerType::SPLINE_FOLLOWER);
goal_builder.add_spline_handle(2);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
WaitForTrajectoryExecution();
@@ -1292,7 +1339,8 @@
spline_goal_builder.add_spline_idx(1);
spline_goal_builder.add_drive_spline_backwards(false);
spline_goal_builder.add_spline(multispline_offset);
- ASSERT_TRUE(builder.Send(spline_goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(spline_goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
// Second spline goal
@@ -1318,14 +1366,16 @@
spline_goal_builder.add_spline_idx(2);
spline_goal_builder.add_drive_spline_backwards(false);
spline_goal_builder.add_spline(multispline_offset);
- ASSERT_TRUE(builder.Send(spline_goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(spline_goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
{
auto builder = drivetrain_goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_controller_type(ControllerType::SPLINE_FOLLOWER);
goal_builder.add_spline_handle(1);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
WaitForTrajectoryExecution();
@@ -1335,7 +1385,8 @@
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_controller_type(ControllerType::SPLINE_FOLLOWER);
goal_builder.add_spline_handle(2);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::milliseconds(4000));
@@ -1367,7 +1418,8 @@
spline_goal_builder.add_spline_idx(1);
spline_goal_builder.add_drive_spline_backwards(false);
spline_goal_builder.add_spline(multispline_offset);
- ASSERT_TRUE(builder.Send(spline_goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(spline_goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
for (int i = 0; i < 100; ++i) {
@@ -1402,7 +1454,8 @@
spline_goal_builder.add_spline_idx(1);
spline_goal_builder.add_drive_spline_backwards(false);
spline_goal_builder.add_spline(multispline_offset);
- ASSERT_TRUE(builder.Send(spline_goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(spline_goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::milliseconds(2000));
@@ -1412,7 +1465,8 @@
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_controller_type(ControllerType::SPLINE_FOLLOWER);
goal_builder.add_spline_handle(1);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
WaitForTrajectoryExecution();
@@ -1434,7 +1488,8 @@
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_controller_type(ControllerType::SPLINE_FOLLOWER);
goal_builder.add_spline_handle(kRunSpline);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
for (size_t spline_index = 0;
spline_index < DrivetrainLoop::kNumSplineFetchers + kExtraSplines;
@@ -1460,7 +1515,8 @@
spline_goal_builder.add_spline_idx(spline_index);
spline_goal_builder.add_drive_spline_backwards(false);
spline_goal_builder.add_spline(multispline_offset);
- ASSERT_TRUE(builder.Send(spline_goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(spline_goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
// Run for at least 2 iterations. Because of how the logic works, there will
// actually typically be a single iteration where we store kNumStoredSplines
// + 1.
@@ -1504,7 +1560,8 @@
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_controller_type(ControllerType::LINE_FOLLOWER);
goal_builder.add_throttle(0.5);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(5));
@@ -1541,7 +1598,8 @@
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_controller_type(ControllerType::LINE_FOLLOWER);
goal_builder.add_throttle(0.5);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(5));
@@ -1564,7 +1622,8 @@
localizer_control_builder.add_x(9.0);
localizer_control_builder.add_y(7.0);
localizer_control_builder.add_theta(1.0);
- ASSERT_TRUE(builder.Send(localizer_control_builder.Finish()));
+ ASSERT_EQ(builder.Send(localizer_control_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(dt());
@@ -1586,7 +1645,8 @@
goal_builder.add_controller_type(ControllerType::MOTION_PROFILE);
goal_builder.add_left_goal(4.0);
goal_builder.add_right_goal(4.0);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(2));
diff --git a/frc971/control_loops/drivetrain/drivetrain_plotter.ts b/frc971/control_loops/drivetrain/drivetrain_plotter.ts
index f55f965..deb300f 100644
--- a/frc971/control_loops/drivetrain/drivetrain_plotter.ts
+++ b/frc971/control_loops/drivetrain/drivetrain_plotter.ts
@@ -24,12 +24,9 @@
'/drivetrain', 'frc971.IMUValuesBatch',
new ImuMessageHandler(conn.getSchema('frc971.IMUValuesBatch')));
- let currentTop = 0;
-
// Polydrivetrain (teleop control) plots
const teleopPlot =
- aosPlotter.addPlot(element, [0, currentTop], [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
- currentTop += DEFAULT_HEIGHT / 2;
+ aosPlotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
teleopPlot.plot.getAxisLabels().setTitle('Drivetrain Teleop Goals');
teleopPlot.plot.getAxisLabels().setXLabel(TIME);
teleopPlot.plot.getAxisLabels().setYLabel('bool, throttle/wheel values');
@@ -44,8 +41,7 @@
// Drivetrain Control Mode
const modePlot =
- aosPlotter.addPlot(element, [0, currentTop], [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
- currentTop += DEFAULT_HEIGHT / 2;
+ aosPlotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
// TODO(james): Actually add enum support.
modePlot.plot.getAxisLabels().setTitle(
'Drivetrain Mode [POLYDRIVE, MOTION_PROFILE, ' +
@@ -58,9 +54,7 @@
controllerType.setDrawLine(false);
// Drivetrain Status estimated relative position
- const positionPlot = aosPlotter.addPlot(element, [0, currentTop],
- [DEFAULT_WIDTH, DEFAULT_HEIGHT]);
- currentTop += DEFAULT_HEIGHT;
+ const positionPlot = aosPlotter.addPlot(element);
positionPlot.plot.getAxisLabels().setTitle("Estimated Relative Position " +
"of the Drivetrain");
positionPlot.plot.getAxisLabels().setXLabel(TIME);
@@ -83,9 +77,7 @@
rightEncoder.setColor(CYAN);
// Drivetrain Output Voltage
- const outputPlot =
- aosPlotter.addPlot(element, [0, currentTop], [DEFAULT_WIDTH, DEFAULT_HEIGHT]);
- currentTop += DEFAULT_HEIGHT;
+ const outputPlot = aosPlotter.addPlot(element);
outputPlot.plot.getAxisLabels().setTitle('Drivetrain Output');
outputPlot.plot.getAxisLabels().setXLabel(TIME);
outputPlot.plot.getAxisLabels().setYLabel('Voltage (V)');
@@ -96,9 +88,7 @@
rightVoltage.setColor(GREEN);
// Voltage Errors
- const voltageErrors =
- aosPlotter.addPlot(element, [0, currentTop], [DEFAULT_WIDTH, DEFAULT_HEIGHT]);
- currentTop += DEFAULT_HEIGHT;
+ const voltageErrors = aosPlotter.addPlot(element);
voltageErrors.plot.getAxisLabels().setTitle('Voltage Errors');
voltageErrors.plot.getAxisLabels().setXLabel(TIME);
voltageErrors.plot.getAxisLabels().setYLabel('Voltage (V)');
@@ -118,9 +108,7 @@
ekfRightVoltageError.setColor(CYAN);
// Sundry components of the output voltages
- const otherVoltages =
- aosPlotter.addPlot(element, [0, currentTop], [DEFAULT_WIDTH, DEFAULT_HEIGHT]);
- currentTop += DEFAULT_HEIGHT;
+ const otherVoltages = aosPlotter.addPlot(element);
otherVoltages.plot.getAxisLabels().setTitle('Other Voltage Components');
otherVoltages.plot.getAxisLabels().setXLabel(TIME);
otherVoltages.plot.getAxisLabels().setYLabel('Voltage (V)');
@@ -144,9 +132,7 @@
uncappedRightVoltage.setDrawLine(false);
// Drivetrain Velocities
- const velocityPlot =
- aosPlotter.addPlot(element, [0, currentTop], [DEFAULT_WIDTH, DEFAULT_HEIGHT]);
- currentTop += DEFAULT_HEIGHT;
+ const velocityPlot = aosPlotter.addPlot(element);
velocityPlot.plot.getAxisLabels().setTitle('Velocity Plots');
velocityPlot.plot.getAxisLabels().setXLabel(TIME);
velocityPlot.plot.getAxisLabels().setYLabel('Wheel Velocity (m/s)');
@@ -183,9 +169,7 @@
rightSpeed.setColor(BROWN);
// Drivetrain trajectory and localizer velocities
- const velocityPlot2 = aosPlotter.addPlot(element, [0, currentTop],
- [DEFAULT_WIDTH, DEFAULT_HEIGHT]);
- currentTop += DEFAULT_HEIGHT;
+ const velocityPlot2 = aosPlotter.addPlot(element);
velocityPlot2.plot.getAxisLabels().setTitle(
"Trajectory and Localizer Velocity Plots");
velocityPlot2.plot.getAxisLabels().setXLabel(TIME);
@@ -221,8 +205,7 @@
splineLateralVelocity.setPointSize(0.0);
// Heading
- const yawPlot = aosPlotter.addPlot(element, [0, currentTop], [DEFAULT_WIDTH, DEFAULT_HEIGHT]);
- currentTop += DEFAULT_HEIGHT;
+ const yawPlot = aosPlotter.addPlot(element);
yawPlot.plot.getAxisLabels().setTitle('Robot Yaw');
yawPlot.plot.getAxisLabels().setXLabel(TIME);
yawPlot.plot.getAxisLabels().setYLabel('Yaw (rad)');
@@ -240,9 +223,7 @@
downEstimatorYaw.setColor(BLUE);
// Pitch/Roll
- const orientationPlot =
- aosPlotter.addPlot(element, [0, currentTop], [DEFAULT_WIDTH, DEFAULT_HEIGHT]);
- currentTop += DEFAULT_HEIGHT;
+ const orientationPlot = aosPlotter.addPlot(element);
orientationPlot.plot.getAxisLabels().setTitle('Orientation');
orientationPlot.plot.getAxisLabels().setXLabel(TIME);
orientationPlot.plot.getAxisLabels().setYLabel('Angle (rad)');
@@ -257,9 +238,7 @@
pitch.setLabel('pitch');
// Accelerometer/Gravity
- const accelPlot =
- aosPlotter.addPlot(element, [0, currentTop], [DEFAULT_WIDTH, DEFAULT_HEIGHT]);
- currentTop += DEFAULT_HEIGHT;
+ const accelPlot = aosPlotter.addPlot(element);
accelPlot.plot.getAxisLabels().setTitle('Accelerometer Readings');
accelPlot.plot.getAxisLabels().setYLabel('Acceleration (g)');
accelPlot.plot.getAxisLabels().setXLabel('Monotonic Reading Time (sec)');
@@ -293,9 +272,7 @@
accelZ.setDrawLine(false);
// Absolute X Position
- const xPositionPlot =
- aosPlotter.addPlot(element, [0, currentTop], [DEFAULT_WIDTH, DEFAULT_HEIGHT]);
- currentTop += DEFAULT_HEIGHT;
+ const xPositionPlot = aosPlotter.addPlot(element);
xPositionPlot.plot.getAxisLabels().setTitle('X Position');
xPositionPlot.plot.getAxisLabels().setXLabel(TIME);
xPositionPlot.plot.getAxisLabels().setYLabel('X Position (m)');
@@ -307,9 +284,7 @@
splineX.setColor(GREEN);
// Absolute Y Position
- const yPositionPlot =
- aosPlotter.addPlot(element, [0, currentTop], [DEFAULT_WIDTH, DEFAULT_HEIGHT]);
- currentTop += DEFAULT_HEIGHT;
+ const yPositionPlot = aosPlotter.addPlot(element);
yPositionPlot.plot.getAxisLabels().setTitle('Y Position');
yPositionPlot.plot.getAxisLabels().setXLabel(TIME);
yPositionPlot.plot.getAxisLabels().setYLabel('Y Position (m)');
@@ -321,9 +296,7 @@
splineY.setColor(GREEN);
// Gyro
- const gyroPlot =
- aosPlotter.addPlot(element, [0, currentTop], [DEFAULT_WIDTH, DEFAULT_HEIGHT]);
- currentTop += DEFAULT_HEIGHT;
+ const gyroPlot = aosPlotter.addPlot(element);
gyroPlot.plot.getAxisLabels().setTitle('Gyro Readings');
gyroPlot.plot.getAxisLabels().setYLabel('Angular Velocity (rad / sec)');
gyroPlot.plot.getAxisLabels().setXLabel('Monotonic Reading Time (sec)');
@@ -353,8 +326,7 @@
// IMU States
const imuStatePlot =
- aosPlotter.addPlot(element, [0, currentTop], [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
- currentTop += DEFAULT_HEIGHT / 2;
+ aosPlotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
imuStatePlot.plot.getAxisLabels().setTitle('IMU State');
imuStatePlot.plot.getAxisLabels().setXLabel(TIME);
imuStatePlot.plot.setDefaultYRange([-0.1, 1.1]);
diff --git a/frc971/control_loops/drivetrain/drivetrain_status.fbs b/frc971/control_loops/drivetrain/drivetrain_status.fbs
index fd3ff0e..f886bb2 100644
--- a/frc971/control_loops/drivetrain/drivetrain_status.fbs
+++ b/frc971/control_loops/drivetrain/drivetrain_status.fbs
@@ -259,6 +259,9 @@
localizer:LocalizerState (id: 26);
zeroing:ImuZeroerState (id: 27);
+
+ // Total number of status send failures.
+ send_failures:uint64 (id: 28);
}
root_type Status;
diff --git a/frc971/control_loops/drivetrain/drivetrain_test_lib.cc b/frc971/control_loops/drivetrain/drivetrain_test_lib.cc
index aabd1c6..fef0d13 100644
--- a/frc971/control_loops/drivetrain/drivetrain_test_lib.cc
+++ b/frc971/control_loops/drivetrain/drivetrain_test_lib.cc
@@ -7,6 +7,7 @@
#include "frc971/control_loops/drivetrain/trajectory.h"
#include "frc971/control_loops/state_feedback_loop.h"
#include "gflags/gflags.h"
+#include "glog/logging.h"
#if defined(SUPPORT_PLOT)
#include "third_party/matplotlib-cpp/matplotlibcpp.h"
#endif
@@ -168,7 +169,8 @@
status_builder.add_x(state_.x());
status_builder.add_y(state_.y());
status_builder.add_theta(state_(2));
- builder.Send(status_builder.Finish());
+ CHECK_EQ(builder.Send(status_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
void DrivetrainSimulation::SendPositionMessage() {
@@ -184,7 +186,8 @@
position_builder.add_right_encoder(right_encoder);
position_builder.add_left_shifter_position(left_gear_high_ ? 1.0 : 0.0);
position_builder.add_right_shifter_position(right_gear_high_ ? 1.0 : 0.0);
- builder.Send(position_builder.Finish());
+ CHECK_EQ(builder.Send(position_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
}
@@ -263,7 +266,8 @@
frc971::IMUValuesBatch::Builder imu_values_batch_builder =
builder.MakeBuilder<frc971::IMUValuesBatch>();
imu_values_batch_builder.add_readings(imu_values_offset);
- builder.Send(imu_values_batch_builder.Finish());
+ CHECK_EQ(builder.Send(imu_values_batch_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
// Simulates the drivetrain moving for one timestep.
diff --git a/frc971/control_loops/drivetrain/robot_state_plotter.ts b/frc971/control_loops/drivetrain/robot_state_plotter.ts
index 829df25..2ce8001 100644
--- a/frc971/control_loops/drivetrain/robot_state_plotter.ts
+++ b/frc971/control_loops/drivetrain/robot_state_plotter.ts
@@ -18,8 +18,7 @@
// Robot Enabled/Disabled and Mode
const robotStatePlot =
- aosPlotter.addPlot(element, [0, currentTop], [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
- currentTop += DEFAULT_HEIGHT / 2;
+ aosPlotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
robotStatePlot.plot.getAxisLabels().setTitle('Robot State');
robotStatePlot.plot.getAxisLabels().setXLabel(TIME);
robotStatePlot.plot.getAxisLabels().setYLabel('bool');
@@ -41,7 +40,7 @@
// Battery Voltage
const batteryPlot =
- aosPlotter.addPlot(element, [0, currentTop], [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
+ aosPlotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
currentTop += DEFAULT_HEIGHT / 2;
batteryPlot.plot.getAxisLabels().setTitle('Battery Voltage');
batteryPlot.plot.getAxisLabels().setXLabel(TIME);
@@ -51,7 +50,7 @@
// PID of process reading sensors
const readerPidPlot =
- aosPlotter.addPlot(element, [0, currentTop], [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
+ aosPlotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
currentTop += DEFAULT_HEIGHT / 2;
readerPidPlot.plot.getAxisLabels().setTitle("PID of Process Reading Sensors");
readerPidPlot.plot.getAxisLabels().setXLabel(TIME);
diff --git a/frc971/control_loops/drivetrain/spline_plotter.ts b/frc971/control_loops/drivetrain/spline_plotter.ts
index 028a3fc..c39afd5 100644
--- a/frc971/control_loops/drivetrain/spline_plotter.ts
+++ b/frc971/control_loops/drivetrain/spline_plotter.ts
@@ -25,7 +25,7 @@
// Polydrivetrain (teleop control) plots
const longitudinalPlot = aosPlotter.addPlot(
- element, [0, currentTop], [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
+ element, [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
currentTop += DEFAULT_HEIGHT / 2;
longitudinalPlot.plot.getAxisLabels().setTitle('Longitudinal Distance');
longitudinalPlot.plot.getAxisLabels().setXLabel(TIME);
@@ -35,7 +35,7 @@
status, ['trajectory_logging', 'distance_remaining']);
const boolPlot = aosPlotter.addPlot(
- element, [0, currentTop], [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
+ element, [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
currentTop += DEFAULT_HEIGHT / 2;
boolPlot.plot.getAxisLabels().setTitle('Bool Flags');
boolPlot.plot.getAxisLabels().setXLabel(TIME);
@@ -46,8 +46,7 @@
boolPlot.addMessageLine(status, ['trajectory_logging', 'is_executed'])
.setColor(BLUE);
- const handlePlot = aosPlotter.addPlot(
- element, [0, currentTop], [DEFAULT_WIDTH, DEFAULT_HEIGHT]);
+ const handlePlot = aosPlotter.addPlot(element);
currentTop += DEFAULT_HEIGHT;
handlePlot.plot.getAxisLabels().setTitle('Spline Handles');
handlePlot.plot.getAxisLabels().setXLabel(TIME);
diff --git a/frc971/control_loops/drivetrain/trajectory_generator.cc b/frc971/control_loops/drivetrain/trajectory_generator.cc
index 16b6809..d022b34 100644
--- a/frc971/control_loops/drivetrain/trajectory_generator.cc
+++ b/frc971/control_loops/drivetrain/trajectory_generator.cc
@@ -22,7 +22,8 @@
aos::Sender<fb::Trajectory>::Builder builder =
trajectory_sender_.MakeBuilder();
- CHECK(builder.Send(trajectory.Serialize(builder.fbb())));
+ CHECK_EQ(builder.Send(trajectory.Serialize(builder.fbb())),
+ aos::RawSender::Error::kOk);
}
} // namespace drivetrain
diff --git a/frc971/control_loops/python/BUILD b/frc971/control_loops/python/BUILD
index a4b8fb8..8679374 100644
--- a/frc971/control_loops/python/BUILD
+++ b/frc971/control_loops/python/BUILD
@@ -26,12 +26,12 @@
],
data = [
"//third_party/cddlib:_cddlib.so",
- "@python_repo//:scipy",
],
target_compatible_with = ["@platforms//cpu:x86_64"],
deps = [
":python_init",
"//external:python-glog",
+ "@python_repo//:scipy",
],
)
@@ -98,6 +98,7 @@
deps = [
":libspline",
":python_init",
+ "@python_repo//:numpy",
],
)
diff --git a/frc971/control_loops/static_zeroing_single_dof_profiled_subsystem_test.cc b/frc971/control_loops/static_zeroing_single_dof_profiled_subsystem_test.cc
index cb0f651..62e3d08 100644
--- a/frc971/control_loops/static_zeroing_single_dof_profiled_subsystem_test.cc
+++ b/frc971/control_loops/static_zeroing_single_dof_profiled_subsystem_test.cc
@@ -14,6 +14,7 @@
#include "frc971/control_loops/static_zeroing_single_dof_profiled_subsystem_test_subsystem_goal_generated.h"
#include "frc971/control_loops/static_zeroing_single_dof_profiled_subsystem_test_subsystem_output_generated.h"
#include "frc971/zeroing/zeroing.h"
+#include "glog/logging.h"
#include "gtest/gtest.h"
using ::frc971::control_loops::PositionSensorSimulator;
@@ -171,7 +172,8 @@
&real_position_builder);
auto position_builder = position.template MakeBuilder<PositionType>();
position_builder.add_position(position_offset);
- position.Send(position_builder.Finish());
+ CHECK_EQ(position.Send(position_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
void set_peak_subsystem_acceleration(double value) {
@@ -331,13 +333,16 @@
status->fbb());
typename StatusType::Builder subsystem_status_builder =
status->template MakeBuilder<StatusType>();
+
subsystem_status_builder.add_status(status_offset);
- status->Send(subsystem_status_builder.Finish());
+ CHECK_EQ(status->Send(subsystem_status_builder.Finish()),
+ aos::RawSender::Error::kOk);
if (output != nullptr) {
typename OutputType::Builder output_builder =
output->template MakeBuilder<OutputType>();
output_builder.add_output(output_voltage);
- output->Send(output_builder.Finish());
+ CHECK_EQ(output->Send(output_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
}
@@ -419,8 +424,9 @@
// Intake system uses 0.05 to test for 0.
{
auto message = this->subsystem_goal_sender_.MakeBuilder();
- EXPECT_TRUE(message.Send(
- zeroing::testing::CreateSubsystemGoal(*message.fbb(), 0.05)));
+ EXPECT_EQ(message.Send(
+ zeroing::testing::CreateSubsystemGoal(*message.fbb(), 0.05)),
+ aos::RawSender::Error::kOk);
}
this->RunFor(chrono::seconds(5));
@@ -437,8 +443,9 @@
message.template MakeBuilder<frc971::ProfileParameters>();
profile_builder.add_max_velocity(1);
profile_builder.add_max_acceleration(0.5);
- EXPECT_TRUE(message.Send(zeroing::testing::CreateSubsystemGoal(
- *message.fbb(), 0.10, profile_builder.Finish())));
+ EXPECT_EQ(message.Send(zeroing::testing::CreateSubsystemGoal(
+ *message.fbb(), 0.10, profile_builder.Finish())),
+ aos::RawSender::Error::kOk);
}
// Give it a lot of time to get there.
@@ -459,8 +466,9 @@
profile_builder.add_max_velocity(std::numeric_limits<double>::quiet_NaN());
profile_builder.add_max_acceleration(
std::numeric_limits<double>::quiet_NaN());
- EXPECT_TRUE(message.Send(zeroing::testing::CreateSubsystemGoal(
- *message.fbb(), 0.10, profile_builder.Finish(), 0.0, true)));
+ EXPECT_EQ(message.Send(zeroing::testing::CreateSubsystemGoal(
+ *message.fbb(), 0.10, profile_builder.Finish(), 0.0, true)),
+ aos::RawSender::Error::kOk);
}
// Give it a lot of time to get there.
@@ -483,12 +491,14 @@
message.template MakeBuilder<frc971::ProfileParameters>();
profile_builder.add_max_velocity(0);
profile_builder.add_max_acceleration(0);
- EXPECT_TRUE(message.Send(zeroing::testing::CreateSubsystemGoal(
- *message.fbb(),
- kStartingGoal + aos::time::DurationInSeconds(
- this->monotonic_now().time_since_epoch()) *
- kVelocity,
- profile_builder.Finish(), kVelocity, true)));
+ EXPECT_EQ(
+ message.Send(zeroing::testing::CreateSubsystemGoal(
+ *message.fbb(),
+ kStartingGoal + aos::time::DurationInSeconds(
+ this->monotonic_now().time_since_epoch()) *
+ kVelocity,
+ profile_builder.Finish(), kVelocity, true)),
+ aos::RawSender::Error::kOk);
},
this->dt());
@@ -514,8 +524,9 @@
// Zero it before we move.
{
auto message = this->subsystem_goal_sender_.MakeBuilder();
- EXPECT_TRUE(message.Send(
- zeroing::testing::CreateSubsystemGoal(*message.fbb(), kRange.upper)));
+ EXPECT_EQ(message.Send(zeroing::testing::CreateSubsystemGoal(*message.fbb(),
+ kRange.upper)),
+ aos::RawSender::Error::kOk);
}
this->RunFor(chrono::seconds(8));
this->VerifyNearGoal();
@@ -528,8 +539,9 @@
message.template MakeBuilder<frc971::ProfileParameters>();
profile_builder.add_max_velocity(20.0);
profile_builder.add_max_acceleration(0.1);
- EXPECT_TRUE(message.Send(zeroing::testing::CreateSubsystemGoal(
- *message.fbb(), kRange.lower, profile_builder.Finish())));
+ EXPECT_EQ(message.Send(zeroing::testing::CreateSubsystemGoal(
+ *message.fbb(), kRange.lower, profile_builder.Finish())),
+ aos::RawSender::Error::kOk);
}
this->set_peak_subsystem_velocity(23.0);
this->set_peak_subsystem_acceleration(0.2);
@@ -544,8 +556,9 @@
message.template MakeBuilder<frc971::ProfileParameters>();
profile_builder.add_max_velocity(0.1);
profile_builder.add_max_acceleration(100.0);
- EXPECT_TRUE(message.Send(zeroing::testing::CreateSubsystemGoal(
- *message.fbb(), kRange.upper, profile_builder.Finish())));
+ EXPECT_EQ(message.Send(zeroing::testing::CreateSubsystemGoal(
+ *message.fbb(), kRange.upper, profile_builder.Finish())),
+ aos::RawSender::Error::kOk);
}
this->set_peak_subsystem_velocity(0.2);
@@ -567,8 +580,9 @@
message.template MakeBuilder<frc971::ProfileParameters>();
profile_builder.add_max_velocity(1.0);
profile_builder.add_max_acceleration(0.5);
- EXPECT_TRUE(message.Send(zeroing::testing::CreateSubsystemGoal(
- *message.fbb(), 100.0, profile_builder.Finish())));
+ EXPECT_EQ(message.Send(zeroing::testing::CreateSubsystemGoal(
+ *message.fbb(), 100.0, profile_builder.Finish())),
+ aos::RawSender::Error::kOk);
}
this->RunFor(chrono::seconds(10));
@@ -584,8 +598,9 @@
message.template MakeBuilder<frc971::ProfileParameters>();
profile_builder.add_max_velocity(1.0);
profile_builder.add_max_acceleration(0.5);
- EXPECT_TRUE(message.Send(zeroing::testing::CreateSubsystemGoal(
- *message.fbb(), -100.0, profile_builder.Finish())));
+ EXPECT_EQ(message.Send(zeroing::testing::CreateSubsystemGoal(
+ *message.fbb(), -100.0, profile_builder.Finish())),
+ aos::RawSender::Error::kOk);
}
this->RunFor(chrono::seconds(10));
@@ -606,8 +621,9 @@
message.template MakeBuilder<frc971::ProfileParameters>();
profile_builder.add_max_velocity(1.0);
profile_builder.add_max_acceleration(0.5);
- EXPECT_TRUE(message.Send(zeroing::testing::CreateSubsystemGoal(
- *message.fbb(), kRange.upper, profile_builder.Finish())));
+ EXPECT_EQ(message.Send(zeroing::testing::CreateSubsystemGoal(
+ *message.fbb(), kRange.upper, profile_builder.Finish())),
+ aos::RawSender::Error::kOk);
}
this->RunFor(chrono::seconds(10));
@@ -628,8 +644,9 @@
this->subsystem_plant_.InitializeSubsystemPosition(kRange.lower_hard);
{
auto message = this->subsystem_goal_sender_.MakeBuilder();
- EXPECT_TRUE(message.Send(
- zeroing::testing::CreateSubsystemGoal(*message.fbb(), kRange.upper)));
+ EXPECT_EQ(message.Send(zeroing::testing::CreateSubsystemGoal(*message.fbb(),
+ kRange.upper)),
+ aos::RawSender::Error::kOk);
}
this->RunFor(chrono::seconds(10));
@@ -643,8 +660,9 @@
this->subsystem_plant_.InitializeSubsystemPosition(kRange.upper_hard);
{
auto message = this->subsystem_goal_sender_.MakeBuilder();
- EXPECT_TRUE(message.Send(
- zeroing::testing::CreateSubsystemGoal(*message.fbb(), kRange.upper)));
+ EXPECT_EQ(message.Send(zeroing::testing::CreateSubsystemGoal(*message.fbb(),
+ kRange.upper)),
+ aos::RawSender::Error::kOk);
}
this->RunFor(chrono::seconds(10));
@@ -658,8 +676,9 @@
this->subsystem_plant_.InitializeSubsystemPosition(kRange.upper);
{
auto message = this->subsystem_goal_sender_.MakeBuilder();
- EXPECT_TRUE(message.Send(zeroing::testing::CreateSubsystemGoal(
- *message.fbb(), kRange.upper - 0.1)));
+ EXPECT_EQ(message.Send(zeroing::testing::CreateSubsystemGoal(
+ *message.fbb(), kRange.upper - 0.1)),
+ aos::RawSender::Error::kOk);
}
this->RunFor(chrono::seconds(10));
@@ -682,8 +701,9 @@
TYPED_TEST_P(IntakeSystemTest, DisabledGoalTest) {
{
auto message = this->subsystem_goal_sender_.MakeBuilder();
- EXPECT_TRUE(message.Send(zeroing::testing::CreateSubsystemGoal(
- *message.fbb(), kRange.lower + 0.03)));
+ EXPECT_EQ(message.Send(zeroing::testing::CreateSubsystemGoal(
+ *message.fbb(), kRange.lower + 0.03)),
+ aos::RawSender::Error::kOk);
}
// Checks that the subsystem has not moved from its starting position at 0
@@ -700,8 +720,9 @@
TYPED_TEST_P(IntakeSystemTest, DisabledZeroTest) {
{
auto message = this->subsystem_goal_sender_.MakeBuilder();
- EXPECT_TRUE(message.Send(
- zeroing::testing::CreateSubsystemGoal(*message.fbb(), kRange.lower)));
+ EXPECT_EQ(message.Send(zeroing::testing::CreateSubsystemGoal(*message.fbb(),
+ kRange.lower)),
+ aos::RawSender::Error::kOk);
}
// Run disabled for 2 seconds
@@ -719,8 +740,9 @@
this->SetEnabled(true);
{
auto message = this->subsystem_goal_sender_.MakeBuilder();
- EXPECT_TRUE(message.Send(zeroing::testing::CreateSubsystemGoal(
- *message.fbb(), kRange.lower_hard)));
+ EXPECT_EQ(message.Send(zeroing::testing::CreateSubsystemGoal(
+ *message.fbb(), kRange.lower_hard)),
+ aos::RawSender::Error::kOk);
}
this->RunFor(chrono::seconds(2));
@@ -753,8 +775,9 @@
{
auto message = this->subsystem_goal_sender_.MakeBuilder();
- EXPECT_TRUE(message.Send(zeroing::testing::CreateSubsystemGoal(
- *message.fbb(), kRange.upper_hard)));
+ EXPECT_EQ(message.Send(zeroing::testing::CreateSubsystemGoal(
+ *message.fbb(), kRange.upper_hard)),
+ aos::RawSender::Error::kOk);
}
this->RunFor(chrono::seconds(2));
diff --git a/frc971/input/drivetrain_input.cc b/frc971/input/drivetrain_input.cc
index b062ceb..b1adf1c 100644
--- a/frc971/input/drivetrain_input.cc
+++ b/frc971/input/drivetrain_input.cc
@@ -114,7 +114,7 @@
goal_builder.add_right_goal(current_right_goal);
goal_builder.add_linear(linear_offset);
- if (!builder.Send(goal_builder.Finish())) {
+ if (builder.Send(goal_builder.Finish()) != aos::RawSender::Error::kOk) {
AOS_LOG(WARNING, "sending stick values failed\n");
}
diff --git a/frc971/vision_codelab/README.md b/frc971/vision_codelab/README.md
new file mode 100755
index 0000000..6a58694
--- /dev/null
+++ b/frc971/vision_codelab/README.md
@@ -0,0 +1,21 @@
+# Vision Codelab
+## Prerequisites: python knowledge, familiarity with pip and numpy (if not, google them and learn!)
+
+In this codelab, you will be writing the vision code for the Galactic Search Challenge
+(detailed on page 18 [here](https://firstfrc.blob.core.windows.net/frc2021/Manual/2021AtHomeChallengesManual.pdf)) from the 2021 at-home skills Challenges.
+
+
+As explained in the manual, balls will be randomly placed in 4 possible configurations (alliance red/blue and field A/B).
+From images of the field, you will be able to determine which path the balls are in so that the robot can drive with that respective spline.
+
+If you are doing this locally and not on the build server, make sure you have python3 and install the needed packages with
+`pip3 install numpy matplotlib opencv-python absl-py glog`
+
+Then, read/watch these opencv tutorials in order, which you will need for the codelab:
+- [Intro](https://www.geeksforgeeks.org/introduction-to-opencv/)
+- [Color spaces](https://www.geeksforgeeks.org/color-spaces-in-opencv-python/?ref=lbp)
+- [Converting between color spaces](https://www.geeksforgeeks.org/python-opencv-cv2-cvtcolor-method/?ref=gcse)
+- MOST IMPORTANT: [Filtering colors](https://pythonprogramming.net/color-filter-python-opencv-tutorial/)
+- [Erosion and dilation](https://www.geeksforgeeks.org/erosion-dilation-images-using-opencv-python/)
+
+Now, follow the TODOs in codelab.py, and run ./codelab_test.py to test your code.
diff --git a/frc971/vision_codelab/blue_a.png b/frc971/vision_codelab/blue_a.png
new file mode 100755
index 0000000..f899c1e
--- /dev/null
+++ b/frc971/vision_codelab/blue_a.png
Binary files differ
diff --git a/frc971/vision_codelab/blue_b.png b/frc971/vision_codelab/blue_b.png
new file mode 100755
index 0000000..9cf2773
--- /dev/null
+++ b/frc971/vision_codelab/blue_b.png
Binary files differ
diff --git a/frc971/vision_codelab/codelab.py b/frc971/vision_codelab/codelab.py
new file mode 100644
index 0000000..617a6a1
--- /dev/null
+++ b/frc971/vision_codelab/codelab.py
@@ -0,0 +1,124 @@
+import cv2 as cv
+import enum
+import numpy as np
+
+
+class Rect:
+ """
+ Holds points for a rectangle in an image.
+ This section of the image is where to expect a ball.
+ """
+
+ # x1 and y1 are top left corner, x2 and y2 are bottom right
+ def __init__(self, x1, y1, x2, y2):
+ self.x1 = x1
+ self.y1 = y1
+ self.x2 = x2
+ self.y2 = y2
+
+ def __str__(self):
+ return "({}, {}), ({}, {})".format(self.x1, self.y1, self.x2, self.y2)
+
+
+class Alliance(enum.Enum):
+ RED = enum.auto()
+ BLUE = enum.auto()
+ UNKNOWN = enum.auto()
+
+
+class Letter(enum.Enum):
+ A = enum.auto()
+ B = enum.auto()
+
+
+class Path:
+ """
+ Each path (ex. Red A, Blue B, etc.) contains a Letter, Alliance, and
+ 2-3 rectangles (the places to expect balls in).
+ There may be only 2 rectangles if there isn't a clear view at all of the balls.
+ """
+
+ def __init__(self, letter, alliance, rects):
+ self.letter = letter
+ self.alliance = alliance
+ self.rects = rects
+
+ def __str__(self):
+ return "%s %s: " % (self.alliance.value, self.letter.value)
+
+
+# TODO: view each of the 4 images in this folder by running `./img_viewer.py <image_file>`,
+# and figure out the retangle bounds for each of the 3 balls in each of the 4 paths.
+# You can move your cursor to the endpoints of the rectangle, and it will show
+# the coordinates.
+# Note that in some images, there might not be a good view of 3 balls and you might have to just use rects of 2.
+# That is ok.
+# Add a new Path to this list for each image.
+PATHS = []
+
+# TODO: fill out the other constants below as you are writing the code in functions
+# galactic_search_path and _pct_yellow
+
+# TODO: figure out the bounds for filtering just like in the video for the red hat.
+# Instead of how the person in the video figured them out, run `./img_viewer.py --hsv <image_file>`
+# to view the images in hsv.
+# Then, move your cursor around the image and it will display the hue, saturation, and value
+# of the pixel you are hovering over. Record the mininum and maximum h, s, and v of all the balls
+# in all photos here.
+LOWER_YELLOW = np.array([0, 0, 0], dtype=np.uint8)
+HIGHER_YELLOW = np.array([255, 255, 255], dtype=np.uint8)
+
+# TODO: once you get to the eroding/dilating step below,
+# tune the kernel by trying different sizes (3, 5 ,7).
+# You can see if your kernel erodes and dilates properly,
+# because when you run the test it will write the image to test_<alliance>_<letter>.png
+# which you can view using img_viewer.py
+# If needed, you can also use different kernels for eroding and dilating.
+KERNEL = np.ones((0, 0), np.uint8)
+
+# Portion of yellow in a rectangle (0 to 1) required for it to be considered as containing a ball.
+# TODO: Try different values for this until it correctly reflects whether a ball is in an rectangle
+# or not.
+BALL_PCT_THRESHOLD = 0
+
+
+def galactic_search_path(img_path):
+ # TODO: read image from img_path into the img variable
+ img = None
+
+ # TODO: convert img into hsv
+ hsv = None
+
+ # TODO: filter yellow using your bounds for yellow and cv.inRange, creating a binary mask
+ mask = None
+
+ # TODO: erode and dilate the mask, and maybe try different numbers of iterations
+ mask = None
+ mask = None
+
+ correct_path = None
+ for path in PATHS:
+ # TODO: If all the percentages are atleast BALL_PCT_THRESHOLD,
+ # then you can say that this path is present on the field and store it.
+ pcts = _pct_yellow(mask, path.rects)
+
+ # TODO: make sure that a path was found, and if not
+ # make sure that correct_path has Alliance.UNKNOWN
+
+ return mask, correct_path
+
+
+# This function finds the percentage of yellow pixels in the rectangles
+# given that are regions of the given image. This allows us to determine
+# whether there is a ball in those rectangles
+def _pct_yellow(mask, rects):
+ pcts = np.zeros(len(rects))
+ for i in range(len(rects)):
+ # TODO: set pcts[i] to be the ratio of the number of yellow pixels in the current rectangle
+ # to the total number of pixels in it.
+ # You can take the section of the mask that is the rectangle, and then count the number of pixels
+ # that aren't zero there with np.count_nonzero to do so,
+ # since mask is a 2d array of either 0 or 255.
+ pass
+
+ return pcts
diff --git a/frc971/vision_codelab/codelab_test.py b/frc971/vision_codelab/codelab_test.py
new file mode 100755
index 0000000..e14d1cd
--- /dev/null
+++ b/frc971/vision_codelab/codelab_test.py
@@ -0,0 +1,41 @@
+#!/usr/bin/python3
+
+import unittest
+import cv2 as cv
+
+import codelab
+
+
+# TODO(milind): this should be integrated with bazel
+class TestCodelab(unittest.TestCase):
+ def codelab_test(self, alliance, letter=None, img_path=None):
+ if img_path is None:
+ img_path = "%s_%s.png" % (alliance.name.lower(),
+ letter.name.lower())
+ mask, path = codelab.galactic_search_path(img_path)
+
+ cv.imwrite("test_" + img_path, mask)
+
+ self.assertEqual(path.alliance, alliance)
+ if letter is not None:
+ self.assertEqual(path.letter, letter)
+
+ def test_red_a(self):
+ self.codelab_test(codelab.Alliance.RED, codelab.Letter.A)
+
+ def test_red_b(self):
+ self.codelab_test(codelab.Alliance.RED, codelab.Letter.B)
+
+ def test_blue_a(self):
+ self.codelab_test(codelab.Alliance.BLUE, codelab.Letter.A)
+
+ def test_blue_b(self):
+ self.codelab_test(codelab.Alliance.BLUE, codelab.Letter.B)
+
+ def test_unknown_path(self):
+ """ Makes sure that Alliance.UNKNOWN is returned when there aren't balls in an image """
+ self.codelab_test(codelab.Alliance.UNKNOWN, img_path="unknown.png")
+
+
+if __name__ == "__main__":
+ unittest.main()
diff --git a/frc971/vision_codelab/img_viewer.py b/frc971/vision_codelab/img_viewer.py
new file mode 100755
index 0000000..fca4e9b
--- /dev/null
+++ b/frc971/vision_codelab/img_viewer.py
@@ -0,0 +1,21 @@
+#!/usr/bin/python3
+
+from absl import app, flags
+import cv2 as cv
+import glog
+import matplotlib.pyplot as plt
+
+flags.DEFINE_bool("hsv", False, "Displays the image in hsv")
+
+
+def main(argv):
+ glog.check_eq(len(argv), 2, "Expected one image filename as an argument")
+ bgr_img = cv.imread(argv[1])
+ img = cv.cvtColor(
+ bgr_img, cv.COLOR_BGR2HSV if flags.FLAGS.hsv else cv.COLOR_BGR2RGB)
+ plt.imshow(img)
+ plt.show()
+
+
+if __name__ == "__main__":
+ app.run(main)
diff --git a/frc971/vision_codelab/red_a.png b/frc971/vision_codelab/red_a.png
new file mode 100755
index 0000000..407fd68
--- /dev/null
+++ b/frc971/vision_codelab/red_a.png
Binary files differ
diff --git a/frc971/vision_codelab/red_b.png b/frc971/vision_codelab/red_b.png
new file mode 100755
index 0000000..e498294
--- /dev/null
+++ b/frc971/vision_codelab/red_b.png
Binary files differ
diff --git a/frc971/vision_codelab/unknown.png b/frc971/vision_codelab/unknown.png
new file mode 100755
index 0000000..14abc6d
--- /dev/null
+++ b/frc971/vision_codelab/unknown.png
Binary files differ
diff --git a/frc971/wpilib/ADIS16448.cc b/frc971/wpilib/ADIS16448.cc
index c047cf9..4be346c 100644
--- a/frc971/wpilib/ADIS16448.cc
+++ b/frc971/wpilib/ADIS16448.cc
@@ -284,7 +284,8 @@
IMUValuesBatch::Builder imu_values_batch_builder =
builder.MakeBuilder<IMUValuesBatch>();
imu_values_batch_builder.add_readings(readings_offset);
- if (!builder.Send(imu_values_batch_builder.Finish())) {
+ if (builder.Send(imu_values_batch_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(WARNING, "sending queue message failed\n");
}
diff --git a/frc971/wpilib/ADIS16470.cc b/frc971/wpilib/ADIS16470.cc
index 151f3e0..b7b315b 100644
--- a/frc971/wpilib/ADIS16470.cc
+++ b/frc971/wpilib/ADIS16470.cc
@@ -263,7 +263,7 @@
IMUValuesBatch::Builder imu_values_batch_builder =
builder.MakeBuilder<IMUValuesBatch>();
imu_values_batch_builder.add_readings(readings_offset);
- builder.Send(imu_values_batch_builder.Finish());
+ builder.CheckOk(builder.Send(imu_values_batch_builder.Finish()));
}
void ADIS16470::DoInitializeStep() {
@@ -388,7 +388,7 @@
IMUValuesBatch::Builder imu_batch_builder =
builder.MakeBuilder<IMUValuesBatch>();
imu_batch_builder.add_readings(readings_offset);
- builder.Send(imu_batch_builder.Finish());
+ builder.CheckOk(builder.Send(imu_batch_builder.Finish()));
if (success) {
state_ = State::kRunning;
} else {
diff --git a/frc971/wpilib/gyro_sender.cc b/frc971/wpilib/gyro_sender.cc
index 9f25d04..ac88acb 100644
--- a/frc971/wpilib/gyro_sender.cc
+++ b/frc971/wpilib/gyro_sender.cc
@@ -54,8 +54,8 @@
AOS_LOG(INFO, "gyro initialized successfully\n");
auto builder = uid_sender_.MakeBuilder();
- builder.Send(
- frc971::sensors::CreateUid(*builder.fbb(), gyro_.ReadPartID()));
+ builder.CheckOk(builder.Send(
+ frc971::sensors::CreateUid(*builder.fbb(), gyro_.ReadPartID())));
}
last_initialize_time_ = monotonic_now;
}
@@ -117,7 +117,7 @@
builder.MakeBuilder<sensors::GyroReading>();
gyro_builder.add_angle(angle_);
gyro_builder.add_velocity(angle_rate + zero_offset_ * kReadingRate);
- builder.Send(gyro_builder.Finish());
+ builder.CheckOk(builder.Send(gyro_builder.Finish()));
} else {
// TODO(brian): Don't break without 6 seconds of standing still before
// enabling. Ideas:
@@ -128,7 +128,7 @@
builder.MakeBuilder<sensors::GyroReading>();
gyro_builder.add_angle(0.0);
gyro_builder.add_velocity(0.0);
- builder.Send(gyro_builder.Finish());
+ builder.CheckOk(builder.Send(gyro_builder.Finish()));
}
zeroing_data_.AddData(new_angle);
diff --git a/frc971/wpilib/imu_plotter.ts b/frc971/wpilib/imu_plotter.ts
index af23ed9..0c735eb 100644
--- a/frc971/wpilib/imu_plotter.ts
+++ b/frc971/wpilib/imu_plotter.ts
@@ -10,7 +10,7 @@
const height = 400;
const aosPlotter = new AosPlotter(conn);
- const accelPlot = aosPlotter.addPlot(element, [0, 0], [width, height]);
+ const accelPlot = aosPlotter.addPlot(element, [width, height]);
accelPlot.plot.getAxisLabels().setTitle('Accelerometer Readings');
accelPlot.plot.getAxisLabels().setYLabel('Acceleration (g)');
accelPlot.plot.getAxisLabels().setXLabel('Monotonic Reading Time (sec)');
@@ -29,7 +29,7 @@
const accelZ = accelPlot.addMessageLine(imu, ['accelerometer_z']);
accelZ.setColor([0, 0, 1]);
- const gyroPlot = aosPlotter.addPlot(element, [0, height], [width, height]);
+ const gyroPlot = aosPlotter.addPlot(element, [width, height]);
gyroPlot.plot.getAxisLabels().setTitle('Gyro Readings');
gyroPlot.plot.getAxisLabels().setYLabel('Angular Velocity (rad / sec)');
gyroPlot.plot.getAxisLabels().setXLabel('Monotonic Reading Time (sec)');
@@ -57,14 +57,14 @@
const gyroZ = gyroPlot.addMessageLine(imu, ['gyro_z']);
gyroZ.setColor([0, 0, 1]);
- const tempPlot = aosPlotter.addPlot(element, [0, height * 2], [width, height / 2]);
+ const tempPlot = aosPlotter.addPlot(element, [width, height / 2]);
tempPlot.plot.getAxisLabels().setTitle('IMU Temperature');
tempPlot.plot.getAxisLabels().setYLabel('Temperature (deg C)');
tempPlot.plot.getAxisLabels().setXLabel('Monotonic Reading Time (sec)');
tempPlot.addMessageLine(imu, ['temperature']);
- const statePlot = aosPlotter.addPlot(element, [0, height * 2.5], [width, height / 2]);
+ const statePlot = aosPlotter.addPlot(element, [width, height / 2]);
statePlot.plot.getAxisLabels().setTitle('IMU State');
statePlot.plot.getAxisLabels().setXLabel('Monotonic Sent Time (sec)');
statePlot.plot.setDefaultYRange([-0.1, 1.1]);
diff --git a/frc971/wpilib/joystick_sender.cc b/frc971/wpilib/joystick_sender.cc
index 5661933..fab3d05 100644
--- a/frc971/wpilib/joystick_sender.cc
+++ b/frc971/wpilib/joystick_sender.cc
@@ -111,7 +111,8 @@
}
joystick_state_builder.add_team_id(team_id_);
- if (!builder.Send(joystick_state_builder.Finish())) {
+ if (builder.Send(joystick_state_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(WARNING, "sending joystick_state failed\n");
}
});
diff --git a/frc971/wpilib/loop_output_handler_test.cc b/frc971/wpilib/loop_output_handler_test.cc
index fcbcbb5..0701bf5 100644
--- a/frc971/wpilib/loop_output_handler_test.cc
+++ b/frc971/wpilib/loop_output_handler_test.cc
@@ -97,7 +97,8 @@
LoopOutputHandlerTestOutput::Builder output_builder =
builder.MakeBuilder<LoopOutputHandlerTestOutput>();
output_builder.add_voltage(5.0);
- EXPECT_TRUE(builder.Send(output_builder.Finish()));
+ EXPECT_EQ(builder.Send(output_builder.Finish()),
+ aos::RawSender::Error::kOk);
++count;
}
diff --git a/frc971/wpilib/pdp_fetcher.cc b/frc971/wpilib/pdp_fetcher.cc
index 62e0e37..0526806 100644
--- a/frc971/wpilib/pdp_fetcher.cc
+++ b/frc971/wpilib/pdp_fetcher.cc
@@ -45,7 +45,7 @@
pdp_builder.add_power(pdp_->GetTotalPower());
pdp_builder.add_currents(currents_offset);
- if (!builder.Send(pdp_builder.Finish())) {
+ if (builder.Send(pdp_builder.Finish()) != aos::RawSender::Error::kOk) {
AOS_LOG(WARNING, "sending pdp values failed\n");
}
}
diff --git a/frc971/wpilib/sensor_reader.cc b/frc971/wpilib/sensor_reader.cc
index f476e71..6c47214 100644
--- a/frc971/wpilib/sensor_reader.cc
+++ b/frc971/wpilib/sensor_reader.cc
@@ -110,7 +110,7 @@
{
auto builder = robot_state_sender_.MakeBuilder();
- builder.Send(::frc971::wpilib::PopulateRobotState(&builder, my_pid_));
+ (void)builder.Send(::frc971::wpilib::PopulateRobotState(&builder, my_pid_));
}
RunIteration();
if (dma_synchronizer_) {
diff --git a/motors/fet12/BUILD b/motors/fet12/BUILD
index ac9849b..be744b2 100644
--- a/motors/fet12/BUILD
+++ b/motors/fet12/BUILD
@@ -84,7 +84,7 @@
srcs = [
"calib_sensors.py",
],
- data = [
+ deps = [
"@python_repo//:scipy",
],
target_compatible_with = ["@platforms//os:linux"],
@@ -95,7 +95,7 @@
srcs = [
"current_equalize.py",
],
- data = [
+ deps = [
":calib_sensors",
"@python_repo//:scipy",
],
diff --git a/motors/python/BUILD b/motors/python/BUILD
index 90ab608..2b2b80b 100644
--- a/motors/python/BUILD
+++ b/motors/python/BUILD
@@ -3,9 +3,6 @@
srcs = [
"big_phase_current.py",
],
- data = [
- "@python_repo//:scipy",
- ],
legacy_create_init = False,
target_compatible_with = ["@platforms//cpu:x86_64"],
deps = [
@@ -14,6 +11,7 @@
"//external:python-glog",
"//frc971/control_loops/python:controls",
"@matplotlib_repo//:matplotlib3",
+ "@python_repo//:scipy",
],
)
diff --git a/third_party/googletest/googlemock/test/BUILD.bazel b/third_party/googletest/googlemock/test/BUILD.bazel
index 2c3f5dc..882a423 100644
--- a/third_party/googletest/googlemock/test/BUILD.bazel
+++ b/third_party/googletest/googlemock/test/BUILD.bazel
@@ -107,7 +107,6 @@
":gmock_output_test_",
":gmock_output_test_golden.txt",
],
- python_version = "PY2",
tags = [
"no_test_msvc2015",
"no_test_msvc2017",
diff --git a/tools/bazel b/tools/bazel
index ef6372b..e72b44e 100755
--- a/tools/bazel
+++ b/tools/bazel
@@ -24,7 +24,7 @@
exec "${BAZEL_OVERRIDE}" "$@"
fi
-readonly VERSION="4.1.0"
+readonly VERSION="4.2.2"
readonly DOWNLOAD_DIR="${HOME}/.cache/bazel"
# Directory to unpack bazel into. This must change whenever bazel changes.
diff --git a/tools/python/BUILD b/tools/python/BUILD
index 2181b31..32093d3 100644
--- a/tools/python/BUILD
+++ b/tools/python/BUILD
@@ -1,9 +1,31 @@
+load("@rules_python//python:defs.bzl", "py_runtime_pair")
+
py_runtime(
- name = "runtime",
+ name = "python3_runtime",
files = [
"runtime_binary.sh",
"@python_repo//:all_files",
],
interpreter = "runtime_binary.sh",
- visibility = ["//visibility:public"],
+ python_version = "PY3",
+)
+
+py_runtime_pair(
+ name = "py_runtime",
+ py2_runtime = None,
+ py3_runtime = ":python3_runtime",
+)
+
+toolchain(
+ name = "python_toolchain",
+ target_compatible_with = [
+ "@platforms//cpu:x86_64",
+ "@platforms//os:linux",
+ ],
+ exec_compatible_with = [
+ "@platforms//cpu:x86_64",
+ "@platforms//os:linux",
+ ],
+ toolchain = ":py_runtime",
+ toolchain_type = "@rules_python//python:toolchain_type",
)
diff --git a/tools/python/runtime_binary.sh b/tools/python/runtime_binary.sh
index 8380424..9cd1519 100755
--- a/tools/python/runtime_binary.sh
+++ b/tools/python/runtime_binary.sh
@@ -36,4 +36,5 @@
export LD_LIBRARY_PATH="${BASE_PATH}/usr/lib/lapack:${BASE_PATH}/usr/lib/libblas:${BASE_PATH}/usr/lib/x86_64-linux-gnu"
-exec "$BASE_PATH"/usr/bin/python3 "$@"
+# Prevent Python from importing the host's installed packages.
+exec "$BASE_PATH"/usr/bin/python3 -sS "$@"
diff --git a/y2012/joystick_reader.cc b/y2012/joystick_reader.cc
index eb8c787..7a8868f 100644
--- a/y2012/joystick_reader.cc
+++ b/y2012/joystick_reader.cc
@@ -114,7 +114,8 @@
goal_builder.add_highgear(is_high_gear_);
goal_builder.add_quickturn(data.IsPressed(kQuickTurn));
- if (!builder.Send(goal_builder.Finish())) {
+ if (builder.Send(goal_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(WARNING, "sending stick values failed\n");
}
}
@@ -135,7 +136,8 @@
builder.MakeBuilder<y2012::control_loops::accessories::Message>();
message_builder.add_solenoids(solenoids_offset);
message_builder.add_sticks(sticks_offset);
- if (!builder.Send(message_builder.Finish())) {
+ if (builder.Send(message_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(WARNING, "sending accessories goal failed\n");
}
}
diff --git a/y2012/wpilib_interface.cc b/y2012/wpilib_interface.cc
index 0d861a0..e3234de 100644
--- a/y2012/wpilib_interface.cc
+++ b/y2012/wpilib_interface.cc
@@ -89,13 +89,13 @@
position_builder.add_right_speed(drivetrain_velocity_translate(
drivetrain_right_encoder_->GetPeriod()));
- builder.Send(position_builder.Finish());
+ builder.CheckOk(builder.Send(position_builder.Finish()));
}
{
auto builder = accessories_position_sender_.MakeBuilder();
- builder.Send(
- builder.MakeBuilder<::aos::control_loops::Position>().Finish());
+ builder.CheckOk(builder.Send(
+ builder.MakeBuilder<::aos::control_loops::Position>().Finish()));
}
}
@@ -182,7 +182,7 @@
builder.MakeBuilder<frc971::wpilib::PneumaticsToLog>();
pcm_->Flush();
to_log_builder.add_read_solenoids(pcm_->GetAll());
- builder.Send(to_log_builder.Finish());
+ builder.CheckOk(builder.Send(to_log_builder.Finish()));
}
}
diff --git a/y2014/actors/autonomous_actor.cc b/y2014/actors/autonomous_actor.cc
index a78ab4b..07c6855 100644
--- a/y2014/actors/autonomous_actor.cc
+++ b/y2014/actors/autonomous_actor.cc
@@ -53,7 +53,7 @@
goal_builder.add_intake(intake_power);
goal_builder.add_centering(centering_power);
- if (!builder.Send(goal_builder.Finish())) {
+ if (builder.Send(goal_builder.Finish()) != aos::RawSender::Error::kOk) {
AOS_LOG(WARNING, "sending claw goal failed\n");
}
}
@@ -66,7 +66,7 @@
goal_builder.add_separation_angle(0.0);
goal_builder.add_intake(12.0);
goal_builder.add_centering(12.0);
- if (!builder.Send(goal_builder.Finish())) {
+ if (builder.Send(goal_builder.Finish()) != aos::RawSender::Error::kOk) {
AOS_LOG(WARNING, "sending claw goal failed\n");
}
}
@@ -81,7 +81,7 @@
goal_builder.add_separation_angle(0.0);
goal_builder.add_intake(4.0);
goal_builder.add_centering(1.0);
- if (!builder.Send(goal_builder.Finish())) {
+ if (builder.Send(goal_builder.Finish()) != aos::RawSender::Error::kOk) {
AOS_LOG(WARNING, "sending claw goal failed\n");
}
}
@@ -94,7 +94,7 @@
goal_builder.add_separation_angle(0.10);
goal_builder.add_intake(4.0);
goal_builder.add_centering(1.0);
- if (!builder.Send(goal_builder.Finish())) {
+ if (builder.Send(goal_builder.Finish()) != aos::RawSender::Error::kOk) {
AOS_LOG(WARNING, "sending claw goal failed\n");
}
}
@@ -108,7 +108,7 @@
goal_builder.add_shot_requested(false);
goal_builder.add_unload_requested(false);
goal_builder.add_load_requested(false);
- if (!builder.Send(goal_builder.Finish())) {
+ if (builder.Send(goal_builder.Finish()) != aos::RawSender::Error::kOk) {
AOS_LOG(WARNING, "sending shooter goal failed\n");
}
}
diff --git a/y2014/actors/shoot_actor.cc b/y2014/actors/shoot_actor.cc
index 095a972..aad64e8 100644
--- a/y2014/actors/shoot_actor.cc
+++ b/y2014/actors/shoot_actor.cc
@@ -63,7 +63,8 @@
claw_builder.add_intake(0.0);
claw_builder.add_centering(0.0);
- if (!builder.Send(claw_builder.Finish())) {
+ if (builder.Send(claw_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(WARNING, "sending claw goal failed\n");
return false;
}
@@ -88,7 +89,8 @@
shooter_builder.add_shot_requested(false);
shooter_builder.add_unload_requested(false);
shooter_builder.add_load_requested(false);
- if (!builder.Send(shooter_builder.Finish())) {
+ if (builder.Send(shooter_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(WARNING, "sending shooter goal failed\n");
return false;
}
@@ -122,7 +124,8 @@
goal_builder.add_shot_requested(true);
goal_builder.add_unload_requested(false);
goal_builder.add_load_requested(false);
- if (!builder.Send(goal_builder.Finish())) {
+ if (builder.Send(goal_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(WARNING, "sending shooter goal failed\n");
return;
}
diff --git a/y2014/control_loops/claw/claw.cc b/y2014/control_loops/claw/claw.cc
index 4f0248c..4b76fd2 100644
--- a/y2014/control_loops/claw/claw.cc
+++ b/y2014/control_loops/claw/claw.cc
@@ -619,8 +619,9 @@
if (::std::isnan(goal->bottom_angle()) ||
::std::isnan(goal->separation_angle()) ||
::std::isnan(goal->intake()) || ::std::isnan(goal->centering())) {
- status->Send(Status::Pack(*status->fbb(), &status_struct));
- output->Send(Output::Pack(*output->fbb(), &output_struct));
+ (void)status->Send(Status::Pack(*status->fbb(), &status_struct));
+ output->CheckOk(
+ output->Send(Output::Pack(*output->fbb(), &output_struct)));
return;
}
}
@@ -977,7 +978,7 @@
output_struct.bottom_claw_voltage = -kMaxVoltage;
}
- output->Send(Output::Pack(*output->fbb(), &output_struct));
+ output->CheckOk(output->Send(Output::Pack(*output->fbb(), &output_struct)));
}
status_struct.bottom = bottom_absolute_position();
@@ -1013,7 +1014,7 @@
bottom_claw_.zeroing_state() ==
ZeroedStateFeedbackLoop::DISABLED_CALIBRATION);
- status->Send(Status::Pack(*status->fbb(), &status_struct));
+ (void)status->Send(Status::Pack(*status->fbb(), &status_struct));
was_enabled_ = enabled;
}
diff --git a/y2014/control_loops/claw/claw_lib_test.cc b/y2014/control_loops/claw/claw_lib_test.cc
index eb941a1..a714124 100644
--- a/y2014/control_loops/claw/claw_lib_test.cc
+++ b/y2014/control_loops/claw/claw_lib_test.cc
@@ -241,7 +241,8 @@
// Only set calibration if it changed last cycle. Calibration starts out
// with a value of 0.
- builder.Send(Position::Pack(*builder.fbb(), &position));
+ EXPECT_EQ(builder.Send(Position::Pack(*builder.fbb(), &position)),
+ aos::RawSender::Error::kOk);
last_position_ = std::move(position);
}
@@ -335,7 +336,8 @@
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_bottom_angle(::std::nan(""));
goal_builder.add_separation_angle(::std::nan(""));
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
SetEnabled(true);
@@ -349,7 +351,8 @@
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_bottom_angle(0.1);
goal_builder.add_separation_angle(0.2);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
SetEnabled(true);
@@ -446,7 +449,8 @@
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_bottom_angle(0.1);
goal_builder.add_separation_angle(0.2);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
SetEnabled(true);
@@ -614,7 +618,8 @@
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_bottom_angle(0.1);
goal_builder.add_separation_angle(0.2);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
TestWindup(ClawMotor::UNKNOWN_LOCATION,
@@ -631,7 +636,8 @@
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_bottom_angle(0.1);
goal_builder.add_separation_angle(0.2);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
TestWindup(ClawMotor::UNKNOWN_LOCATION,
@@ -648,7 +654,8 @@
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_bottom_angle(0.1);
goal_builder.add_separation_angle(0.2);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
TestWindup(ClawMotor::FINE_TUNE_BOTTOM,
diff --git a/y2014/control_loops/shooter/shooter.cc b/y2014/control_loops/shooter/shooter.cc
index 230a048..2a3e0d0 100644
--- a/y2014/control_loops/shooter/shooter.cc
+++ b/y2014/control_loops/shooter/shooter.cc
@@ -656,7 +656,7 @@
output_struct.latch_piston = latch_piston_;
output_struct.brake_piston = brake_piston_;
- output->Send(Output::Pack(*output->fbb(), &output_struct));
+ output->CheckOk(output->Send(Output::Pack(*output->fbb(), &output_struct)));
}
if (position) {
@@ -676,7 +676,7 @@
status_builder.add_shots(shot_count_);
- status->Send(status_builder.Finish());
+ (void)status->Send(status_builder.Finish());
}
flatbuffers::Offset<Output> ShooterMotor::Zero(
diff --git a/y2014/control_loops/shooter/shooter_lib_test.cc b/y2014/control_loops/shooter/shooter_lib_test.cc
index d3217a6..f7dcf20 100644
--- a/y2014/control_loops/shooter/shooter_lib_test.cc
+++ b/y2014/control_loops/shooter/shooter_lib_test.cc
@@ -199,7 +199,8 @@
*last_position_message_.pusher_proximal.get(),
values.shooter.pusher_proximal, last_position_);
- builder.Send(Position::Pack(*builder.fbb(), &position));
+ EXPECT_EQ(builder.Send(Position::Pack(*builder.fbb(), &position)),
+ aos::RawSender::Error::kOk);
last_position_ = position.position;
last_position_message_ = std::move(position);
@@ -403,7 +404,8 @@
::aos::Sender<Goal>::Builder builder = shooter_goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_shot_power(70.0);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(2));
@@ -422,7 +424,8 @@
::aos::Sender<Goal>::Builder builder = shooter_goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_shot_power(70.0);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::milliseconds(1200));
EXPECT_EQ(ShooterMotor::STATE_READY, shooter_motor_.state());
@@ -431,7 +434,8 @@
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_shot_power(35.0);
goal_builder.add_shot_requested(true);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
bool hit_fire = false;
@@ -445,7 +449,8 @@
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_shot_power(17.0);
goal_builder.add_shot_requested(false);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
hit_fire = true;
}
@@ -467,7 +472,8 @@
::aos::Sender<Goal>::Builder builder = shooter_goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_shot_power(70.0);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::milliseconds(1500));
@@ -477,7 +483,8 @@
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_shot_power(0.0);
goal_builder.add_shot_requested(true);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
bool hit_fire = false;
@@ -490,7 +497,8 @@
shooter_goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_shot_requested(false);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
hit_fire = true;
}
@@ -513,7 +521,8 @@
::aos::Sender<Goal>::Builder builder = shooter_goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_shot_power(500.0);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
while (test_event_loop_->monotonic_now() <
monotonic_clock::time_point(chrono::milliseconds(1600))) {
@@ -531,7 +540,8 @@
::aos::Sender<Goal>::Builder builder = shooter_goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_shot_power(70.0);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::milliseconds(1500));
@@ -540,7 +550,8 @@
::aos::Sender<Goal>::Builder builder = shooter_goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_shot_power(14.0);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::milliseconds(500));
@@ -559,7 +570,8 @@
::aos::Sender<Goal>::Builder builder = shooter_goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_shot_power(70.0);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::milliseconds(1500));
EXPECT_EQ(ShooterMotor::STATE_READY, shooter_motor_.state());
@@ -567,7 +579,8 @@
::aos::Sender<Goal>::Builder builder = shooter_goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_unload_requested(true);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
while (test_event_loop_->monotonic_now() <
@@ -588,7 +601,8 @@
::aos::Sender<Goal>::Builder builder = shooter_goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_shot_power(70);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::milliseconds(1500));
@@ -601,7 +615,8 @@
::aos::Sender<Goal>::Builder builder = shooter_goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_unload_requested(true);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
while (test_event_loop_->monotonic_now() <
@@ -622,7 +637,8 @@
::aos::Sender<Goal>::Builder builder = shooter_goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_shot_power(70);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::milliseconds(1500));
EXPECT_EQ(ShooterMotor::STATE_READY, shooter_motor_.state());
@@ -630,7 +646,8 @@
::aos::Sender<Goal>::Builder builder = shooter_goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_unload_requested(true);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
int kicked_delay = 20;
@@ -665,7 +682,8 @@
::aos::Sender<Goal>::Builder builder = shooter_goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_shot_power(70);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::milliseconds(1500));
EXPECT_EQ(ShooterMotor::STATE_READY, shooter_motor_.state());
@@ -673,7 +691,8 @@
::aos::Sender<Goal>::Builder builder = shooter_goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_unload_requested(true);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
int kicked_delay = 20;
@@ -713,7 +732,8 @@
::aos::Sender<Goal>::Builder builder = shooter_goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_shot_power(70.0);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(2));
// EXPECT_NEAR(0.0, shooter_motor_.GetPosition(), 0.01);
@@ -734,7 +754,8 @@
::aos::Sender<Goal>::Builder builder = shooter_goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_shot_power(70.0);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(3));
// EXPECT_NEAR(0.0, shooter_motor_.GetPosition(), 0.01);
@@ -765,7 +786,8 @@
::aos::Sender<Goal>::Builder builder = shooter_goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_shot_power(120.0);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
while (test_event_loop_->monotonic_now() <
monotonic_clock::time_point(chrono::seconds(2))) {
diff --git a/y2014/hot_goal_reader.cc b/y2014/hot_goal_reader.cc
index 5972a92..71380f4 100644
--- a/y2014/hot_goal_reader.cc
+++ b/y2014/hot_goal_reader.cc
@@ -89,7 +89,7 @@
builder.MakeBuilder<y2014::HotGoal>();
hot_goal_builder.add_left_count(left_count);
hot_goal_builder.add_right_count(right_count);
- builder.Send(hot_goal_builder.Finish());
+ (void)builder.Send(hot_goal_builder.Finish());
} break;
case 0:
AOS_LOG(WARNING, "read on %d timed out\n", connection);
diff --git a/y2014/joystick_reader.cc b/y2014/joystick_reader.cc
index d1569d7..fc78994 100644
--- a/y2014/joystick_reader.cc
+++ b/y2014/joystick_reader.cc
@@ -393,7 +393,8 @@
: (data.IsPressed(kRollersOut) ? -12.0 : intake_power_));
goal_builder.add_centering(intaking ? 12.0 : 0.0);
- if (!builder.Send(goal_builder.Finish())) {
+ if (builder.Send(goal_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(WARNING, "sending claw goal failed\n");
}
}
@@ -406,7 +407,8 @@
goal_builder.add_shot_requested(data.IsPressed(kFire));
goal_builder.add_unload_requested(data.IsPressed(kUnload));
goal_builder.add_load_requested(data.IsPressed(kReload));
- if (!builder.Send(goal_builder.Finish())) {
+ if (builder.Send(goal_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(WARNING, "sending shooter goal failed\n");
}
}
diff --git a/y2014/wpilib_interface.cc b/y2014/wpilib_interface.cc
index 3e34064..9f8e2ce 100644
--- a/y2014/wpilib_interface.cc
+++ b/y2014/wpilib_interface.cc
@@ -271,7 +271,7 @@
position_builder.add_right_shifter_position(
hall_translate(values.right_drive, low_right_hall, high_right_hall));
- builder.Send(position_builder.Finish());
+ builder.CheckOk(builder.Send(position_builder.Finish()));
}
{
@@ -279,7 +279,7 @@
y2014::sensors::AutoMode::Builder auto_builder =
builder.MakeBuilder<y2014::sensors::AutoMode>();
auto_builder.add_voltage(auto_selector_analog_->GetVoltage());
- builder.Send(auto_builder.Finish());
+ builder.CheckOk(builder.Send(auto_builder.Finish()));
}
}
@@ -310,7 +310,7 @@
position_builder.add_pusher_distal(pusher_distal_offset);
position_builder.add_pusher_proximal(pusher_proximal_offset);
- builder.Send(position_builder.Finish());
+ builder.CheckOk(builder.Send(position_builder.Finish()));
}
{
@@ -325,7 +325,7 @@
position_builder.add_top(top_offset);
position_builder.add_bottom(bottom_offset);
- builder.Send(position_builder.Finish());
+ builder.CheckOk(builder.Send(position_builder.Finish()));
}
}
@@ -558,7 +558,7 @@
pcm_->Flush();
to_log_builder.add_read_solenoids(pcm_->GetAll());
- builder.Send(to_log_builder.Finish());
+ (void)builder.Send(to_log_builder.Finish());
}
}
diff --git a/y2014_bot3/control_loops/rollers/rollers.cc b/y2014_bot3/control_loops/rollers/rollers.cc
index 5fcb692..8cf7ba6 100644
--- a/y2014_bot3/control_loops/rollers/rollers.cc
+++ b/y2014_bot3/control_loops/rollers/rollers.cc
@@ -22,7 +22,7 @@
constexpr double k2014Bot3LowGoalForwardVoltage = 6.0;
constexpr double k2014Bot3LowGoalBackwardVoltage = -6.0;
- status->Send(status->MakeBuilder<Status>().Finish());
+ status->CheckOk(status->Send(status->MakeBuilder<Status>().Finish()));
if (!output || !goal) {
return;
@@ -80,7 +80,7 @@
output_struct.back_intake_voltage = -k2014Bot3IntakeForwardVoltage;
}
- output->Send(Output::Pack(*output->fbb(), &output_struct));
+ output->CheckOk(output->Send(Output::Pack(*output->fbb(), &output_struct)));
}
} // namespace rollers
diff --git a/y2014_bot3/joystick_reader.cc b/y2014_bot3/joystick_reader.cc
index 3d1159a..5c27247 100644
--- a/y2014_bot3/joystick_reader.cc
+++ b/y2014_bot3/joystick_reader.cc
@@ -99,8 +99,9 @@
} else if (data.IsPressed(kHumanPlayer)) {
rollers_goal.human_player = true;
}
- if (!builder.Send(control_loops::rollers::Goal::Pack(*builder.fbb(),
- &rollers_goal))) {
+ if (builder.Send(control_loops::rollers::Goal::Pack(*builder.fbb(),
+ &rollers_goal)) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(WARNING, "Sending rollers values failed.\n");
}
}
diff --git a/y2014_bot3/wpilib_interface.cc b/y2014_bot3/wpilib_interface.cc
index b4de681..2c7c521 100644
--- a/y2014_bot3/wpilib_interface.cc
+++ b/y2014_bot3/wpilib_interface.cc
@@ -102,14 +102,14 @@
position_builder.add_right_speed(drivetrain_velocity_translate(
drivetrain_right_encoder_->GetPeriod()));
- builder.Send(position_builder.Finish());
+ builder.CheckOk(builder.Send(position_builder.Finish()));
}
// Rollers
{
auto builder = rollers_position_sender_.MakeBuilder();
- builder.Send(
- builder.MakeBuilder<control_loops::rollers::Position>().Finish());
+ builder.CheckOk(builder.Send(
+ builder.MakeBuilder<control_loops::rollers::Position>().Finish()));
}
}
@@ -212,7 +212,7 @@
pcm_->Flush();
to_log_builder.add_read_solenoids(pcm_->GetAll());
- builder.Send(to_log_builder.Finish());
+ builder.CheckOk(builder.Send(to_log_builder.Finish()));
}
}
diff --git a/y2016/actors/autonomous_actor.cc b/y2016/actors/autonomous_actor.cc
index c35612f..6401b27 100644
--- a/y2016/actors/autonomous_actor.cc
+++ b/y2016/actors/autonomous_actor.cc
@@ -120,7 +120,8 @@
superstructure_goal_builder.add_voltage_climber(0.0);
superstructure_goal_builder.add_unfold_climber(false);
- if (!builder.Send(superstructure_goal_builder.Finish())) {
+ if (builder.Send(superstructure_goal_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(ERROR, "Sending superstructure goal failed.\n");
}
}
@@ -135,7 +136,8 @@
shooter_goal_builder.add_clamp_open(true);
shooter_goal_builder.add_push_to_shooter(false);
shooter_goal_builder.add_force_lights_on(false);
- if (!builder.Send(shooter_goal_builder.Finish())) {
+ if (builder.Send(shooter_goal_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(ERROR, "Sending shooter goal failed.\n");
}
}
@@ -150,8 +152,8 @@
shooter_goal_builder.add_clamp_open(false);
shooter_goal_builder.add_push_to_shooter(false);
shooter_goal_builder.add_force_lights_on(false);
-
- if (!builder.Send(shooter_goal_builder.Finish())) {
+ if (builder.Send(shooter_goal_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(ERROR, "Sending shooter goal failed.\n");
}
}
@@ -171,7 +173,8 @@
shooter_goal_builder.add_push_to_shooter(false);
shooter_goal_builder.add_force_lights_on(force_lights_on);
- if (!builder.Send(shooter_goal_builder.Finish())) {
+ if (builder.Send(shooter_goal_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(ERROR, "Sending shooter goal failed.\n");
}
}
@@ -196,7 +199,8 @@
shooter_goal_builder.add_push_to_shooter(true);
shooter_goal_builder.add_force_lights_on(force_lights_on);
- if (!builder.Send(shooter_goal_builder.Finish())) {
+ if (builder.Send(shooter_goal_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(ERROR, "Sending shooter goal failed.\n");
}
diff --git a/y2016/actors/superstructure_actor.cc b/y2016/actors/superstructure_actor.cc
index e193243..d33b125 100644
--- a/y2016/actors/superstructure_actor.cc
+++ b/y2016/actors/superstructure_actor.cc
@@ -72,7 +72,8 @@
superstructure_goal_builder.add_voltage_climber(0.0);
superstructure_goal_builder.add_unfold_climber(unfold_climber);
- if (!builder.Send(superstructure_goal_builder.Finish())) {
+ if (builder.Send(superstructure_goal_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(ERROR, "Sending superstructure move failed.\n");
}
}
diff --git a/y2016/actors/vision_align_actor.cc b/y2016/actors/vision_align_actor.cc
index 56a858c..cf50331 100644
--- a/y2016/actors/vision_align_actor.cc
+++ b/y2016/actors/vision_align_actor.cc
@@ -79,7 +79,8 @@
goal_builder.add_left_goal(left_current + side_distance_change);
goal_builder.add_right_goal(right_current - side_distance_change);
- if (!builder.Send(goal_builder.Finish())) {
+ if (builder.Send(goal_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(WARNING, "sending drivetrain goal failed\n");
}
}
diff --git a/y2016/control_loops/shooter/shooter.cc b/y2016/control_loops/shooter/shooter.cc
index 8b719c3..d317d4f 100644
--- a/y2016/control_loops/shooter/shooter.cc
+++ b/y2016/control_loops/shooter/shooter.cc
@@ -186,12 +186,12 @@
output_builder.add_push_to_shooter(shoot);
}
- output->Send(output_builder.Finish());
+ output->CheckOk(output->Send(output_builder.Finish()));
}
status_builder.add_shots(shots_);
- status->Send(status_builder.Finish());
+ (void)status->Send(status_builder.Finish());
}
} // namespace shooter
diff --git a/y2016/control_loops/shooter/shooter_lib_test.cc b/y2016/control_loops/shooter/shooter_lib_test.cc
index 6934a75..46b96c0 100644
--- a/y2016/control_loops/shooter/shooter_lib_test.cc
+++ b/y2016/control_loops/shooter/shooter_lib_test.cc
@@ -76,7 +76,8 @@
position_builder.add_theta_left(shooter_plant_left_->Y(0, 0));
position_builder.add_theta_right(shooter_plant_right_->Y(0, 0));
- builder.Send(position_builder.Finish());
+ EXPECT_EQ(builder.Send(position_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
void set_left_voltage_offset(double voltage_offset) {
@@ -172,7 +173,8 @@
auto builder = shooter_goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_angular_velocity(0.0);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(dt() * 3 / 2);
@@ -193,7 +195,8 @@
auto builder = shooter_goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_angular_velocity(450.0);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(1));
@@ -204,7 +207,8 @@
auto builder = shooter_goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_angular_velocity(0.0);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
// Make sure we don't apply voltage on spin-down.
@@ -230,7 +234,8 @@
auto builder = shooter_goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_angular_velocity(20.0);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
// Cause problems by adding a voltage error on one side.
shooter_plant_.set_right_voltage_offset(-4.0);
@@ -267,7 +272,8 @@
auto builder = shooter_goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_angular_velocity(200.0);
- EXPECT_TRUE(builder.Send(goal_builder.Finish()));
+ EXPECT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(5));
EXPECT_TRUE(shooter_output_fetcher_.Fetch());
diff --git a/y2016/control_loops/superstructure/superstructure.cc b/y2016/control_loops/superstructure/superstructure.cc
index 3ee7730..88dfd93 100644
--- a/y2016/control_loops/superstructure/superstructure.cc
+++ b/y2016/control_loops/superstructure/superstructure.cc
@@ -742,7 +742,7 @@
output_struct.traverse_down = unsafe_goal->traverse_down();
}
- output->Send(Output::Pack(*output->fbb(), &output_struct));
+ output->CheckOk(output->Send(Output::Pack(*output->fbb(), &output_struct)));
}
// Save debug/internal state.
@@ -827,7 +827,7 @@
status_builder.add_state(state_);
status_builder.add_is_collided(is_collided);
- status->Send(status_builder.Finish());
+ (void)status->Send(status_builder.Finish());
last_state_ = state_before_switch;
}
diff --git a/y2016/control_loops/superstructure/superstructure_lib_test.cc b/y2016/control_loops/superstructure/superstructure_lib_test.cc
index 49ae033..12ef0a2 100644
--- a/y2016/control_loops/superstructure/superstructure_lib_test.cc
+++ b/y2016/control_loops/superstructure/superstructure_lib_test.cc
@@ -166,7 +166,8 @@
position_builder.add_shoulder(shoulder_offset);
position_builder.add_wrist(wrist_offset);
- builder.Send(position_builder.Finish());
+ EXPECT_EQ(builder.Send(position_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
double shoulder_angle() const { return arm_plant_->X(0, 0); }
@@ -417,7 +418,8 @@
goal_builder.add_max_angular_acceleration_intake(20);
goal_builder.add_max_angular_acceleration_shoulder(20);
goal_builder.add_max_angular_acceleration_wrist(20);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(5));
@@ -440,7 +442,8 @@
goal_builder.add_max_angular_acceleration_shoulder(20);
goal_builder.add_max_angular_velocity_wrist(20);
goal_builder.add_max_angular_acceleration_wrist(20);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
// Give it a lot of time to get there.
@@ -466,7 +469,8 @@
goal_builder.add_max_angular_acceleration_shoulder(20);
goal_builder.add_max_angular_velocity_wrist(20);
goal_builder.add_max_angular_acceleration_wrist(20);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(10));
@@ -493,7 +497,8 @@
goal_builder.add_max_angular_acceleration_shoulder(20);
goal_builder.add_max_angular_velocity_wrist(20);
goal_builder.add_max_angular_acceleration_wrist(20);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(10));
@@ -521,7 +526,8 @@
goal_builder.add_max_angular_acceleration_shoulder(20);
goal_builder.add_max_angular_velocity_wrist(20);
goal_builder.add_max_angular_acceleration_wrist(20);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(10));
@@ -550,7 +556,8 @@
goal_builder.add_max_angular_acceleration_shoulder(20);
goal_builder.add_max_angular_velocity_wrist(20);
goal_builder.add_max_angular_acceleration_wrist(20);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(10));
@@ -585,7 +592,8 @@
goal_builder.add_angle_shoulder(constants::Values::kShoulderRange.upper);
goal_builder.add_angle_wrist(constants::Values::kWristRange.upper +
constants::Values::kShoulderRange.upper);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
// We have to wait for it to put the elevator in a safe position as well.
RunFor(chrono::seconds(15));
@@ -608,7 +616,8 @@
goal_builder.add_angle_intake(constants::Values::kIntakeRange.lower);
goal_builder.add_angle_shoulder(constants::Values::kShoulderRange.lower);
goal_builder.add_angle_wrist(0.0);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
// We have to wait for it to put the superstructure in a safe position as
// well.
@@ -633,7 +642,8 @@
goal_builder.add_angle_intake(constants::Values::kIntakeRange.lower + 0.3);
goal_builder.add_angle_shoulder(constants::Values::kShoulderRange.upper);
goal_builder.add_angle_wrist(0.0);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(15));
@@ -659,7 +669,8 @@
goal_builder.add_angle_shoulder(constants::Values::kShoulderRange.lower +
0.03);
goal_builder.add_angle_wrist(constants::Values::kWristRange.lower + 0.03);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::milliseconds(100));
@@ -697,7 +708,8 @@
goal_builder.add_max_angular_acceleration_shoulder(20);
goal_builder.add_max_angular_velocity_wrist(20);
goal_builder.add_max_angular_acceleration_wrist(20);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
// Expected states to cycle through and check in order.
@@ -769,7 +781,8 @@
goal_builder.add_max_angular_acceleration_shoulder(20);
goal_builder.add_max_angular_velocity_wrist(20);
goal_builder.add_max_angular_acceleration_wrist(20);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
// Expected states to cycle through and check in order.
@@ -846,7 +859,8 @@
goal_builder.add_angle_intake(0.0);
goal_builder.add_angle_shoulder(0.0);
goal_builder.add_angle_wrist(0.0);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(8));
@@ -870,7 +884,8 @@
goal_builder.add_angle_shoulder(
constants::Values::kShoulderEncoderIndexDifference * 10);
goal_builder.add_angle_wrist(0.0);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
// Run disabled for 2 seconds
@@ -925,7 +940,8 @@
goal_builder.add_max_angular_acceleration_shoulder(20);
goal_builder.add_max_angular_velocity_wrist(20);
goal_builder.add_max_angular_acceleration_wrist(20);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(6));
@@ -945,7 +961,8 @@
goal_builder.add_max_angular_acceleration_shoulder(1);
goal_builder.add_max_angular_velocity_wrist(1);
goal_builder.add_max_angular_acceleration_wrist(1);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
// TODO(austin): The profile isn't feasible, so when we try to track it, we
@@ -974,7 +991,8 @@
goal_builder.add_max_angular_acceleration_shoulder(20);
goal_builder.add_max_angular_velocity_wrist(20);
goal_builder.add_max_angular_acceleration_wrist(20);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(6));
@@ -994,7 +1012,8 @@
goal_builder.add_max_angular_acceleration_shoulder(1);
goal_builder.add_max_angular_velocity_wrist(1);
goal_builder.add_max_angular_acceleration_wrist(1);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
superstructure_plant_.set_peak_intake_acceleration(1.20);
@@ -1021,7 +1040,8 @@
goal_builder.add_max_angular_acceleration_shoulder(20);
goal_builder.add_max_angular_velocity_wrist(20);
goal_builder.add_max_angular_acceleration_wrist(20);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(6));
@@ -1042,7 +1062,8 @@
goal_builder.add_max_angular_acceleration_shoulder(1);
goal_builder.add_max_angular_velocity_wrist(1);
goal_builder.add_max_angular_acceleration_wrist(1);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
superstructure_plant_.set_peak_intake_acceleration(1.05);
@@ -1070,7 +1091,8 @@
goal_builder.add_max_angular_acceleration_shoulder(20);
goal_builder.add_max_angular_velocity_wrist(20);
goal_builder.add_max_angular_acceleration_wrist(20);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(6));
@@ -1091,7 +1113,8 @@
goal_builder.add_max_angular_acceleration_shoulder(100);
goal_builder.add_max_angular_velocity_wrist(1);
goal_builder.add_max_angular_acceleration_wrist(100);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
superstructure_plant_.set_peak_intake_velocity(4.65);
@@ -1118,7 +1141,8 @@
goal_builder.add_max_angular_acceleration_shoulder(20);
goal_builder.add_max_angular_velocity_wrist(20);
goal_builder.add_max_angular_acceleration_wrist(20);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(6));
@@ -1138,7 +1162,8 @@
goal_builder.add_max_angular_acceleration_shoulder(20);
goal_builder.add_max_angular_velocity_wrist(1);
goal_builder.add_max_angular_acceleration_wrist(100);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
superstructure_plant_.set_peak_intake_velocity(1.0);
@@ -1166,7 +1191,8 @@
goal_builder.add_max_angular_acceleration_shoulder(20);
goal_builder.add_max_angular_velocity_wrist(20);
goal_builder.add_max_angular_acceleration_wrist(20);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(6));
@@ -1187,7 +1213,8 @@
goal_builder.add_max_angular_acceleration_shoulder(1.0);
goal_builder.add_max_angular_velocity_wrist(10.0);
goal_builder.add_max_angular_acceleration_wrist(160.0);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
superstructure_plant_.set_peak_intake_velocity(1.0);
@@ -1215,7 +1242,8 @@
goal_builder.add_angle_shoulder(
constants::Values::kShoulderRange.lower); // Down
goal_builder.add_angle_wrist(0.0); // Stowed
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(15));
@@ -1227,7 +1255,8 @@
constants::Values::kIntakeRange.upper); // stowed
goal_builder.add_angle_shoulder(M_PI / 4.0); // in the collision area
goal_builder.add_angle_wrist(M_PI / 2.0); // down
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(5));
@@ -1259,7 +1288,8 @@
constants::Values::kIntakeRange.upper); // stowed
goal_builder.add_angle_shoulder(M_PI / 2.0); // in the collision area
goal_builder.add_angle_wrist(M_PI); // forward
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(5));
@@ -1280,7 +1310,8 @@
goal_builder.add_angle_intake(0.0);
goal_builder.add_angle_shoulder(0.0);
goal_builder.add_angle_wrist(M_PI); // intentionally asking for forward
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(15));
@@ -1307,7 +1338,8 @@
goal_builder.add_angle_intake(0.0);
goal_builder.add_angle_shoulder(M_PI * 0.5);
goal_builder.add_angle_wrist(0.0);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(6));
@@ -1348,7 +1380,8 @@
goal_builder.add_angle_intake(0.0);
goal_builder.add_angle_shoulder(constants::Values::kShoulderRange.lower);
goal_builder.add_angle_wrist(0.0);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(6));
@@ -1392,7 +1425,8 @@
goal_builder.add_angle_intake(0.0);
goal_builder.add_angle_shoulder(constants::Values::kShoulderRange.lower);
goal_builder.add_angle_wrist(0.0); // intentionally asking for forward
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(6));
@@ -1421,7 +1455,8 @@
goal_builder.add_angle_intake(0.0);
goal_builder.add_angle_shoulder(M_PI * 0.25);
goal_builder.add_angle_wrist(0.0);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(8));
@@ -1438,7 +1473,8 @@
goal_builder.add_max_angular_acceleration_shoulder(20);
goal_builder.add_max_angular_velocity_wrist(20);
goal_builder.add_max_angular_acceleration_wrist(20);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
// Wait until we hit the transition point.
@@ -1462,7 +1498,8 @@
goal_builder.add_angle_intake(0.0);
goal_builder.add_angle_shoulder(0.0);
goal_builder.add_angle_wrist(0.0);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(8));
@@ -1479,7 +1516,8 @@
goal_builder.add_max_angular_acceleration_shoulder(20);
goal_builder.add_max_angular_velocity_wrist(20);
goal_builder.add_max_angular_acceleration_wrist(20);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
// Wait until we hit the transition point.
diff --git a/y2016/joystick_reader.cc b/y2016/joystick_reader.cc
index 974adf7..b235f64 100644
--- a/y2016/joystick_reader.cc
+++ b/y2016/joystick_reader.cc
@@ -381,7 +381,8 @@
superstructure_builder.add_traverse_down(traverse_down_);
superstructure_builder.add_force_intake(true);
- if (!builder.Send(superstructure_builder.Finish())) {
+ if (builder.Send(superstructure_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(ERROR, "Sending superstructure goal failed.\n");
} else {
AOS_LOG(DEBUG, "sending goals: intake: %f, shoulder: %f, wrist: %f\n",
@@ -399,7 +400,8 @@
shooter_builder.add_force_lights_on(force_lights_on);
shooter_builder.add_shooting_forwards(wrist_goal_ > 0);
- if (!builder.Send(shooter_builder.Finish())) {
+ if (builder.Send(shooter_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(ERROR, "Sending shooter goal failed.\n");
}
}
diff --git a/y2016/vision/target_receiver.cc b/y2016/vision/target_receiver.cc
index a762e4f..75a07a8 100644
--- a/y2016/vision/target_receiver.cc
+++ b/y2016/vision/target_receiver.cc
@@ -408,8 +408,9 @@
}
if (drivetrain_offset.CompleteVisionStatus(&new_vision_status)) {
- if (!builder.Send(
- VisionStatus::Pack(*builder.fbb(), &new_vision_status))) {
+ if (builder.Send(
+ VisionStatus::Pack(*builder.fbb(), &new_vision_status)) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(ERROR, "Failed to send vision information\n");
}
} else {
diff --git a/y2016/wpilib_interface.cc b/y2016/wpilib_interface.cc
index e3d367c..0419950 100644
--- a/y2016/wpilib_interface.cc
+++ b/y2016/wpilib_interface.cc
@@ -276,7 +276,7 @@
position_builder.add_right_shifter_position(
hall_translate(drivetrain_right_hall_->GetVoltage()));
- builder.Send(position_builder.Finish());
+ builder.CheckOk(builder.Send(position_builder.Finish()));
}
}
@@ -290,7 +290,7 @@
shooter_translate(-shooter_left_encoder_->GetRaw()));
shooter_builder.add_theta_right(
shooter_translate(shooter_right_encoder_->GetRaw()));
- builder.Send(shooter_builder.Finish());
+ builder.CheckOk(builder.Send(shooter_builder.Finish()));
}
{
@@ -321,7 +321,7 @@
position_builder.add_shoulder(shoulder_offset);
position_builder.add_wrist(wrist_offset);
- builder.Send(position_builder.Finish());
+ builder.CheckOk(builder.Send(position_builder.Finish()));
}
{
@@ -329,7 +329,7 @@
::y2016::sensors::BallDetector::Builder ball_detector_builder =
builder.MakeBuilder<y2016::sensors::BallDetector>();
ball_detector_builder.add_voltage(ball_detector_->GetVoltage());
- builder.Send(ball_detector_builder.Finish());
+ builder.CheckOk(builder.Send(ball_detector_builder.Finish()));
}
{
@@ -343,7 +343,7 @@
}
}
auto_builder.add_mode(mode);
- builder.Send(auto_builder.Finish());
+ builder.CheckOk(builder.Send(auto_builder.Finish()));
}
}
@@ -492,7 +492,7 @@
pcm_->Flush();
to_log_builder.add_read_solenoids(pcm_->GetAll());
- builder.Send(to_log_builder.Finish());
+ (void)builder.Send(to_log_builder.Finish());
}
}
diff --git a/y2017/actors/autonomous_actor.h b/y2017/actors/autonomous_actor.h
index f0bcfc8..5eed336 100644
--- a/y2017/actors/autonomous_actor.h
+++ b/y2017/actors/autonomous_actor.h
@@ -165,7 +165,7 @@
goal->mutable_indexer()->mutate_voltage_rollers(0.0);
}
- if (!builder.Send(goal_offset)) {
+ if (builder.Send(goal_offset) != aos::RawSender::Error::kOk) {
AOS_LOG(ERROR, "Sending superstructure goal failed.\n");
}
}
diff --git a/y2017/control_loops/superstructure/superstructure.cc b/y2017/control_loops/superstructure/superstructure.cc
index c707653..84da59c 100644
--- a/y2017/control_loops/superstructure/superstructure.cc
+++ b/y2017/control_loops/superstructure/superstructure.cc
@@ -260,10 +260,10 @@
}
if (output) {
- output->Send(Output::Pack(*output->fbb(), &output_struct));
+ output->CheckOk(output->Send(Output::Pack(*output->fbb(), &output_struct)));
}
- status->Send(status_builder.Finish());
+ (void)status->Send(status_builder.Finish());
}
} // namespace superstructure
diff --git a/y2017/control_loops/superstructure/superstructure_lib_test.cc b/y2017/control_loops/superstructure/superstructure_lib_test.cc
index 7690937..05ca333 100644
--- a/y2017/control_loops/superstructure/superstructure_lib_test.cc
+++ b/y2017/control_loops/superstructure/superstructure_lib_test.cc
@@ -246,7 +246,8 @@
position_builder.add_intake(intake_offset);
position_builder.add_hood(hood_offset);
- builder.Send(position_builder.Finish());
+ ASSERT_EQ(builder.Send(position_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
double hood_position() const { return hood_plant_->X(0, 0); }
@@ -635,7 +636,8 @@
goal_builder.add_shooter(shooter_offset);
goal_builder.add_indexer(indexer_offset);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(5));
@@ -691,7 +693,8 @@
goal_builder.add_shooter(shooter_offset);
goal_builder.add_indexer(indexer_offset);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
// Give it a lot of time to get there.
@@ -738,7 +741,8 @@
goal_builder.add_shooter(shooter_offset);
goal_builder.add_indexer(indexer_offset);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(8));
VerifyNearGoal();
@@ -789,7 +793,8 @@
goal_builder.add_shooter(shooter_offset);
goal_builder.add_indexer(indexer_offset);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
superstructure_plant_.set_peak_intake_velocity(23.0);
superstructure_plant_.set_peak_turret_velocity(23.0);
@@ -844,7 +849,8 @@
goal_builder.add_shooter(shooter_offset);
goal_builder.add_indexer(indexer_offset);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
superstructure_plant_.set_peak_intake_velocity(0.2);
@@ -906,7 +912,8 @@
goal_builder.add_shooter(shooter_offset);
goal_builder.add_indexer(indexer_offset);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(10));
@@ -964,7 +971,8 @@
goal_builder.add_shooter(shooter_offset);
goal_builder.add_indexer(indexer_offset);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(10));
@@ -1024,7 +1032,8 @@
goal_builder.add_shooter(shooter_offset);
goal_builder.add_indexer(indexer_offset);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(10));
@@ -1086,7 +1095,8 @@
goal_builder.add_shooter(shooter_offset);
goal_builder.add_indexer(indexer_offset);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(10));
@@ -1144,7 +1154,8 @@
goal_builder.add_shooter(shooter_offset);
goal_builder.add_indexer(indexer_offset);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(10));
@@ -1192,7 +1203,8 @@
goal_builder.add_shooter(shooter_offset);
goal_builder.add_indexer(indexer_offset);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(10));
@@ -1239,7 +1251,8 @@
goal_builder.add_shooter(shooter_offset);
goal_builder.add_indexer(indexer_offset);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(10));
@@ -1271,7 +1284,8 @@
auto builder = superstructure_goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
{
auto builder = superstructure_goal_sender_.MakeBuilder();
@@ -1303,7 +1317,8 @@
goal_builder.add_shooter(shooter_offset);
goal_builder.add_indexer(indexer_offset);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::milliseconds(100));
@@ -1356,7 +1371,8 @@
goal_builder.add_shooter(shooter_offset);
goal_builder.add_indexer(indexer_offset);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
// Run disabled for 2 seconds
@@ -1426,7 +1442,8 @@
goal_builder.add_indexer(indexer_offset);
goal_builder.add_shooter(shooter_offset);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(5));
@@ -1462,7 +1479,8 @@
goal_builder.add_indexer(indexer_offset);
goal_builder.add_shooter(shooter_offset);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
// Make sure we don't apply voltage on spin-down.
@@ -1508,7 +1526,8 @@
goal_builder.add_indexer(indexer_offset);
goal_builder.add_shooter(shooter_offset);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(5));
EXPECT_EQ(nullptr, superstructure_output_fetcher_.get());
@@ -1554,7 +1573,8 @@
goal_builder.add_indexer(indexer_offset);
goal_builder.add_shooter(shooter_offset);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(5));
@@ -1656,7 +1676,8 @@
goal_builder.add_indexer(indexer_offset);
goal_builder.add_shooter(shooter_offset);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(5));
diff --git a/y2017/control_loops/superstructure/vision_time_adjuster_test.cc b/y2017/control_loops/superstructure/vision_time_adjuster_test.cc
index d7a5fb4..49e4460 100644
--- a/y2017/control_loops/superstructure/vision_time_adjuster_test.cc
+++ b/y2017/control_loops/superstructure/vision_time_adjuster_test.cc
@@ -19,8 +19,7 @@
: ::testing::Test(),
configuration_(aos::configuration::ReadConfig("y2017/config.json")),
event_loop_factory_(&configuration_.message()),
- simulation_event_loop_(
- event_loop_factory_.MakeEventLoop("drivetrain")),
+ simulation_event_loop_(event_loop_factory_.MakeEventLoop("drivetrain")),
drivetrain_status_sender_(
simulation_event_loop_
->MakeSender<::frc971::control_loops::drivetrain::Status>(
@@ -99,7 +98,8 @@
status_builder.add_estimated_left_position(drivetrain_left_);
status_builder.add_estimated_right_position(drivetrain_right_);
- ASSERT_TRUE(builder.Send(status_builder.Finish()));
+ ASSERT_EQ(builder.Send(status_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
void SendVisionTarget() {
@@ -118,7 +118,8 @@
drivetrain_history_[0]);
vision_status_builder.add_image_valid(true);
- ASSERT_TRUE(builder.Send(vision_status_builder.Finish()));
+ ASSERT_EQ(builder.Send(vision_status_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
double GetDriveTrainAngle() const {
diff --git a/y2017/joystick_reader.cc b/y2017/joystick_reader.cc
index 13b8720..cb21d3e 100644
--- a/y2017/joystick_reader.cc
+++ b/y2017/joystick_reader.cc
@@ -292,7 +292,8 @@
goal_builder.add_hood(hood_goal_offset);
goal_builder.add_shooter(shooter_goal_offset);
- if (!builder.Send(goal_builder.Finish())) {
+ if (builder.Send(goal_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(ERROR, "Sending superstructure goal failed.\n");
}
}
diff --git a/y2017/vision/target_receiver.cc b/y2017/vision/target_receiver.cc
index 84d3428..ba09425 100644
--- a/y2017/vision/target_receiver.cc
+++ b/y2017/vision/target_receiver.cc
@@ -48,7 +48,7 @@
builder.MakeBuilder<VisionStatus>();
vision_status_builder.add_image_valid(target.has_target());
if (target.has_target()) {
- vision_status_builder.add_target_time (
+ vision_status_builder.add_target_time(
std::chrono::duration_cast<std::chrono::nanoseconds>(
target_time.time_since_epoch())
.count());
@@ -57,13 +57,14 @@
double angle = 0.0;
finder.GetAngleDist(
aos::vision::Vector<2>(target.target().x(), target.target().y()),
- /* TODO: Insert down estimate here in radians: */ 0.0,
- &distance, &angle);
+ /* TODO: Insert down estimate here in radians: */ 0.0, &distance,
+ &angle);
vision_status_builder.add_distance(distance);
vision_status_builder.add_angle(angle);
}
- if (!builder.Send(vision_status_builder.Finish())) {
+ if (builder.Send(vision_status_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(ERROR, "Failed to send vision information\n");
}
}
diff --git a/y2017/wpilib_interface.cc b/y2017/wpilib_interface.cc
index 04e19b6..6a4596e 100644
--- a/y2017/wpilib_interface.cc
+++ b/y2017/wpilib_interface.cc
@@ -222,7 +222,7 @@
position_builder.add_left_speed(
drivetrain_velocity_translate(drivetrain_left_encoder_->GetPeriod()));
- builder.Send(position_builder.Finish());
+ builder.CheckOk(builder.Send(position_builder.Finish()));
}
}
@@ -278,7 +278,7 @@
Values::kShooterEncoderCountsPerRevolution,
Values::kShooterEncoderRatio));
- builder.Send(position_builder.Finish());
+ builder.CheckOk(builder.Send(position_builder.Finish()));
}
{
@@ -293,7 +293,7 @@
}
}
auto_builder.add_mode(mode);
- builder.Send(auto_builder.Finish());
+ builder.CheckOk(builder.Send(auto_builder.Finish()));
}
}
diff --git a/y2018/actors/autonomous_actor.h b/y2018/actors/autonomous_actor.h
index 014459a..67d9c84 100644
--- a/y2018/actors/autonomous_actor.h
+++ b/y2018/actors/autonomous_actor.h
@@ -105,7 +105,8 @@
superstructure_builder.add_deploy_fork(deploy_fork_);
superstructure_builder.add_trajectory_override(false);
- if (!builder.Send(superstructure_builder.Finish())) {
+ if (builder.Send(superstructure_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(ERROR, "Sending superstructure goal failed.\n");
}
}
diff --git a/y2018/control_loops/python/BUILD b/y2018/control_loops/python/BUILD
index 3c75b97..c74396c 100644
--- a/y2018/control_loops/python/BUILD
+++ b/y2018/control_loops/python/BUILD
@@ -172,8 +172,6 @@
"graph_generate.py",
],
legacy_create_init = False,
- python_version = "PY3",
- srcs_version = "PY3",
target_compatible_with = ["@platforms//cpu:x86_64"],
deps = [
":python_init",
@@ -190,11 +188,10 @@
"graph_generate.py",
],
legacy_create_init = False,
- python_version = "PY2",
- srcs_version = "PY2",
target_compatible_with = ["@platforms//os:linux"],
deps = [
":python_init",
+ "@python_repo//:numpy",
],
)
diff --git a/y2018/control_loops/superstructure/superstructure.cc b/y2018/control_loops/superstructure/superstructure.cc
index 7d12fd5..fc08280 100644
--- a/y2018/control_loops/superstructure/superstructure.cc
+++ b/y2018/control_loops/superstructure/superstructure.cc
@@ -329,10 +329,10 @@
output_builder.add_forks_release(forks_release_output);
output_builder.add_voltage_winch(voltage_winch_output);
- output->Send(output_builder.Finish());
+ output->CheckOk(output->Send(output_builder.Finish()));
}
- status->Send(status_builder.Finish());
+ (void)status->Send(status_builder.Finish());
}
void Superstructure::SendColors(float red, float green, float blue) {
@@ -344,7 +344,8 @@
status_light_builder.add_green(green);
status_light_builder.add_blue(blue);
- if (!builder.Send(status_light_builder.Finish())) {
+ if (builder.Send(status_light_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(ERROR, "Failed to send lights.\n");
}
}
diff --git a/y2018/control_loops/superstructure/superstructure_lib_test.cc b/y2018/control_loops/superstructure/superstructure_lib_test.cc
index 9d2c10e..c52d8db 100644
--- a/y2018/control_loops/superstructure/superstructure_lib_test.cc
+++ b/y2018/control_loops/superstructure/superstructure_lib_test.cc
@@ -262,7 +262,8 @@
position_builder.add_left_intake(left_intake_offset);
position_builder.add_right_intake(right_intake_offset);
position_builder.add_arm(arm_offset);
- EXPECT_TRUE(builder.Send(position_builder.Finish()));
+ EXPECT_EQ(builder.Send(position_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
// Sets the difference between the commanded and applied powers.
@@ -409,7 +410,8 @@
goal_builder.add_arm_goal_position(arm::UpIndex());
goal_builder.add_open_claw(true);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
// Give it a lot of time to get there.
@@ -440,7 +442,8 @@
goal_builder.add_arm_goal_position(arm::UpIndex());
goal_builder.add_open_claw(true);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
// Give it a lot of time to get there.
@@ -469,7 +472,8 @@
goal_builder.add_arm_goal_position(arm::UpIndex());
goal_builder.add_open_claw(true);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(10));
@@ -508,7 +512,8 @@
goal_builder.add_arm_goal_position(arm::UpIndex());
goal_builder.add_open_claw(true);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(10));
@@ -552,7 +557,8 @@
goal_builder.add_arm_goal_position(arm::UpIndex());
goal_builder.add_open_claw(true);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(10));
{
@@ -570,7 +576,8 @@
goal_builder.add_arm_goal_position(arm::UpIndex());
goal_builder.add_open_claw(true);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(10));
VerifyNearGoal();
@@ -598,7 +605,8 @@
goal_builder.add_arm_goal_position(arm::UpIndex());
goal_builder.add_open_claw(true);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(10));
@@ -627,7 +635,8 @@
goal_builder.add_arm_goal_position(arm::UpIndex());
goal_builder.add_open_claw(true);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(10));
@@ -675,7 +684,8 @@
goal_builder.add_arm_goal_position(arm::FrontHighBoxIndex());
goal_builder.add_open_claw(true);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
EXPECT_EQ(arm::Arm::State::RUNNING, superstructure_.arm().state());
@@ -699,7 +709,8 @@
goal_builder.add_arm_goal_position(arm::FrontHighBoxIndex());
goal_builder.add_open_claw(true);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(10));
@@ -721,7 +732,8 @@
goal_builder.add_arm_goal_position(arm::ReadyAboveBoxIndex());
goal_builder.add_open_claw(true);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(10));
@@ -748,7 +760,8 @@
goal_builder.add_arm_goal_position(arm::BackLowBoxIndex());
goal_builder.add_open_claw(true);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(10));
@@ -770,7 +783,8 @@
goal_builder.add_arm_goal_position(arm::ReadyAboveBoxIndex());
goal_builder.add_open_claw(true);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(10));
diff --git a/y2018/joystick_reader.cc b/y2018/joystick_reader.cc
index 42620ff..3a5ed63 100644
--- a/y2018/joystick_reader.cc
+++ b/y2018/joystick_reader.cc
@@ -351,7 +351,8 @@
superstructure_builder.add_open_claw(false);
}
- if (!builder.Send(superstructure_builder.Finish())) {
+ if (builder.Send(superstructure_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(ERROR, "Sending superstructure goal failed.\n");
}
diff --git a/y2018/vision/vision_status.cc b/y2018/vision/vision_status.cc
index 15daefc..ca11dd8 100644
--- a/y2018/vision/vision_status.cc
+++ b/y2018/vision/vision_status.cc
@@ -35,7 +35,8 @@
builder.MakeBuilder<VisionStatus>();
vision_status_builder.add_high_frame_count(status.high_frame_count());
vision_status_builder.add_low_frame_count(status.low_frame_count());
- if (!builder.Send(vision_status_builder.Finish())) {
+ if (builder.Send(vision_status_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(ERROR, "Failed to send vision information\n");
}
}
diff --git a/y2018/wpilib_interface.cc b/y2018/wpilib_interface.cc
index ef4c058..4ee8031 100644
--- a/y2018/wpilib_interface.cc
+++ b/y2018/wpilib_interface.cc
@@ -293,7 +293,7 @@
drivetrain_shifter_pot_translate(
right_drivetrain_shifter_->GetVoltage()));
- builder.Send(drivetrain_builder.Finish());
+ builder.CheckOk(builder.Send(drivetrain_builder.Finish()));
}
}
@@ -396,7 +396,7 @@
superstructure_builder.add_box_distance(lidar_lite_.last_width() /
0.00001 / 100.0 / 2);
- builder.Send(superstructure_builder.Finish());
+ builder.CheckOk(builder.Send(superstructure_builder.Finish()));
}
}
@@ -516,7 +516,7 @@
pcm_->Flush();
to_log_builder.add_read_solenoids(pcm_->GetAll());
- builder.Send(to_log_builder.Finish());
+ (void)builder.Send(to_log_builder.Finish());
}
monotonic_clock::time_point monotonic_now = event_loop_->monotonic_now();
diff --git a/y2019/actors/autonomous_actor.cc b/y2019/actors/autonomous_actor.cc
index 7622a64..ad5bd5b 100644
--- a/y2019/actors/autonomous_actor.cc
+++ b/y2019/actors/autonomous_actor.cc
@@ -98,7 +98,8 @@
localizer_control_builder.add_y(1.35 * turn_scalar);
localizer_control_builder.add_theta(M_PI);
localizer_control_builder.add_theta_uncertainty(0.00001);
- if (!builder.Send(localizer_control_builder.Finish())) {
+ if (builder.Send(localizer_control_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(ERROR, "Failed to reset localizer.\n");
}
}
diff --git a/y2019/actors/autonomous_actor.h b/y2019/actors/autonomous_actor.h
index af2a60f..c0792b8 100644
--- a/y2019/actors/autonomous_actor.h
+++ b/y2019/actors/autonomous_actor.h
@@ -153,7 +153,8 @@
superstructure_builder.add_intake(intake_offset);
superstructure_builder.add_suction(suction_offset);
- if (!builder.Send(superstructure_builder.Finish())) {
+ if (builder.Send(superstructure_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(ERROR, "Sending superstructure goal failed.\n");
}
}
diff --git a/y2019/control_loops/drivetrain/localized_drivetrain_test.cc b/y2019/control_loops/drivetrain/localized_drivetrain_test.cc
index 485dff6..4d6f84a 100644
--- a/y2019/control_loops/drivetrain/localized_drivetrain_test.cc
+++ b/y2019/control_loops/drivetrain/localized_drivetrain_test.cc
@@ -160,8 +160,10 @@
::std::get<0>(camera_delay_queue_.front()) <
monotonic_now() - camera_latency) {
auto builder = camera_sender_.MakeBuilder();
- ASSERT_TRUE(builder.Send(CameraFrame::Pack(
- *builder.fbb(), ::std::get<1>(camera_delay_queue_.front()).get())));
+ ASSERT_EQ(builder.Send(CameraFrame::Pack(
+ *builder.fbb(),
+ ::std::get<1>(camera_delay_queue_.front()).get())),
+ aos::RawSender::Error::kOk);
camera_delay_queue_.pop();
}
}
@@ -216,7 +218,8 @@
drivetrain_builder.add_left_goal(-1.0);
drivetrain_builder.add_right_goal(1.0);
- EXPECT_TRUE(builder.Send(drivetrain_builder.Finish()));
+ EXPECT_EQ(builder.Send(drivetrain_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(3));
VerifyNearGoal();
@@ -237,7 +240,8 @@
drivetrain_builder.add_left_goal(-1.0);
drivetrain_builder.add_right_goal(1.0);
- EXPECT_TRUE(builder.Send(drivetrain_builder.Finish()));
+ EXPECT_EQ(builder.Send(drivetrain_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(3));
VerifyNearGoal();
@@ -257,7 +261,8 @@
drivetrain_builder.add_left_goal(-1.0);
drivetrain_builder.add_right_goal(1.0);
- EXPECT_TRUE(builder.Send(drivetrain_builder.Finish()));
+ EXPECT_EQ(builder.Send(drivetrain_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(3));
VerifyNearGoal();
@@ -279,7 +284,8 @@
drivetrain_builder.add_left_goal(-1.0);
drivetrain_builder.add_right_goal(1.0);
- EXPECT_TRUE(builder.Send(drivetrain_builder.Finish()));
+ EXPECT_EQ(builder.Send(drivetrain_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(3));
// VerifyNearGoal succeeds because it is just checking wheel positions:
@@ -308,7 +314,8 @@
drivetrain_builder.add_left_goal(-1.0);
drivetrain_builder.add_right_goal(1.0);
- EXPECT_TRUE(builder.Send(drivetrain_builder.Finish()));
+ EXPECT_EQ(builder.Send(drivetrain_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
{
@@ -321,7 +328,8 @@
localizer_control_builder.add_y(drivetrain_plant_.state().y());
localizer_control_builder.add_theta(drivetrain_plant_.state()(2, 0));
- EXPECT_TRUE(builder.Send(localizer_control_builder.Finish()));
+ EXPECT_EQ(builder.Send(localizer_control_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(3));
VerifyNearGoal();
@@ -344,7 +352,8 @@
drivetrain_builder.add_left_goal(-1.0);
drivetrain_builder.add_right_goal(1.0);
- EXPECT_TRUE(builder.Send(drivetrain_builder.Finish()));
+ EXPECT_EQ(builder.Send(drivetrain_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(5));
VerifyNearGoal(4e-3);
@@ -373,7 +382,8 @@
frc971::control_loops::drivetrain::ControllerType::LINE_FOLLOWER);
drivetrain_builder.add_throttle(0.5);
- EXPECT_TRUE(builder.Send(drivetrain_builder.Finish()));
+ EXPECT_EQ(builder.Send(drivetrain_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(6));
diff --git a/y2019/control_loops/drivetrain/target_selector_test.cc b/y2019/control_loops/drivetrain/target_selector_test.cc
index 5933f3f..f33224b 100644
--- a/y2019/control_loops/drivetrain/target_selector_test.cc
+++ b/y2019/control_loops/drivetrain/target_selector_test.cc
@@ -39,8 +39,7 @@
TargetSelectorParamTest()
: configuration_(aos::configuration::ReadConfig("y2019/config.json")),
event_loop_factory_(&configuration_.message()),
- event_loop_(
- this->event_loop_factory_.MakeEventLoop("drivetrain")),
+ event_loop_(this->event_loop_factory_.MakeEventLoop("drivetrain")),
test_event_loop_(this->event_loop_factory_.MakeEventLoop("test")),
target_selector_hint_sender_(
test_event_loop_->MakeSender<
@@ -82,12 +81,14 @@
builder.MakeBuilder<superstructure::Goal>();
goal_builder.add_suction(suction_offset);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
{
auto builder = target_selector_hint_sender_.MakeBuilder();
- ASSERT_TRUE(builder.Send(drivetrain::CreateTargetSelectorHint(
- *builder.fbb(), GetParam().selection_hint)));
+ ASSERT_EQ(builder.Send(drivetrain::CreateTargetSelectorHint(
+ *builder.fbb(), GetParam().selection_hint)),
+ aos::RawSender::Error::kOk);
}
bool expect_target = GetParam().expect_target;
const State state = GetParam().state;
diff --git a/y2019/control_loops/superstructure/superstructure.cc b/y2019/control_loops/superstructure/superstructure.cc
index 9e7a5fe..e796f0b 100644
--- a/y2019/control_loops/superstructure/superstructure.cc
+++ b/y2019/control_loops/superstructure/superstructure.cc
@@ -119,7 +119,7 @@
output_struct.intake_roller_voltage = 0.0;
}
- output->Send(Output::Pack(*output->fbb(), &output_struct));
+ output->CheckOk(output->Send(Output::Pack(*output->fbb(), &output_struct)));
}
if (unsafe_goal) {
@@ -196,7 +196,7 @@
}
}
- status->Send(status_offset);
+ (void)status->Send(status_offset);
}
void Superstructure::SendColors(float red, float green, float blue) {
@@ -208,7 +208,8 @@
status_light_builder.add_green(green);
status_light_builder.add_blue(blue);
- if (!builder.Send(status_light_builder.Finish())) {
+ if (builder.Send(status_light_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(ERROR, "Failed to send lights.\n");
}
}
diff --git a/y2019/control_loops/superstructure/superstructure_lib_test.cc b/y2019/control_loops/superstructure/superstructure_lib_test.cc
index cabb4e2..d6b4f2d 100644
--- a/y2019/control_loops/superstructure/superstructure_lib_test.cc
+++ b/y2019/control_loops/superstructure/superstructure_lib_test.cc
@@ -7,6 +7,7 @@
#include "frc971/control_loops/control_loop_test.h"
#include "frc971/control_loops/position_sensor_sim.h"
#include "frc971/control_loops/team_number_test_environment.h"
+#include "glog/logging.h"
#include "gtest/gtest.h"
#include "y2019/constants.h"
#include "y2019/control_loops/superstructure/elevator/elevator_plant.h"
@@ -166,7 +167,8 @@
position_builder.add_stilts(stilts_offset);
position_builder.add_suction_pressure(simulated_pressure_);
- builder.Send(position_builder.Finish());
+ CHECK_EQ(builder.Send(position_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
double elevator_position() const { return elevator_plant_->X(0, 0); }
@@ -501,7 +503,8 @@
goal_builder.add_intake(intake_offset);
goal_builder.add_stilts(stilts_offset);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(10));
VerifyNearGoal();
@@ -550,7 +553,8 @@
goal_builder.add_intake(intake_offset);
goal_builder.add_stilts(stilts_offset);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
// Give it a lot of time to get there.
@@ -593,7 +597,8 @@
goal_builder.add_intake(intake_offset);
goal_builder.add_stilts(stilts_offset);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(8));
VerifyNearGoal();
@@ -630,7 +635,8 @@
goal_builder.add_intake(intake_offset);
goal_builder.add_stilts(stilts_offset);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
superstructure_plant_.set_peak_elevator_velocity(23.0);
superstructure_plant_.set_peak_elevator_acceleration(0.2);
@@ -682,7 +688,8 @@
goal_builder.add_intake(intake_offset);
goal_builder.add_stilts(stilts_offset);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
WaitUntilZeroed();
VerifyNearGoal();
@@ -743,7 +750,8 @@
goal_builder.add_intake(intake_offset);
goal_builder.add_stilts(stilts_offset);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
// Give it a lot of time to get there.
@@ -783,7 +791,8 @@
goal_builder.add_stilts(stilts_offset);
goal_builder.add_roller_voltage(6.0);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(5));
@@ -818,7 +827,8 @@
goal_builder.add_stilts(stilts_offset);
goal_builder.add_roller_voltage(6.0);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(5));
@@ -860,7 +870,8 @@
goal_builder.add_stilts(stilts_offset);
goal_builder.add_suction(suction_offset);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(Vacuum::kTimeAtHigherVoltage - chrono::milliseconds(10));
@@ -904,7 +915,8 @@
goal_builder.add_stilts(stilts_offset);
goal_builder.add_suction(suction_offset);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
// Verify that at 0 pressure after short time voltage is still high
@@ -954,7 +966,8 @@
goal_builder.add_stilts(stilts_offset);
goal_builder.add_suction(suction_offset);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
// Get a Gamepiece
@@ -991,7 +1004,8 @@
goal_builder.add_stilts(stilts_offset);
goal_builder.add_suction(suction_offset);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
superstructure_plant_.set_simulated_pressure(1.0);
diff --git a/y2019/joystick_reader.cc b/y2019/joystick_reader.cc
index a92dd90..51aeffb 100644
--- a/y2019/joystick_reader.cc
+++ b/y2019/joystick_reader.cc
@@ -283,7 +283,8 @@
control_loops::drivetrain::SelectionHint::NONE);
}
}
- if (!builder.Send(target_selector_hint_builder.Finish())) {
+ if (builder.Send(target_selector_hint_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(ERROR, "Failed to send target selector hint.\n");
}
}
@@ -297,7 +298,8 @@
localizer_control_builder.add_y(3.4);
localizer_control_builder.add_keep_current_theta(true);
- if (!builder.Send(localizer_control_builder.Finish())) {
+ if (builder.Send(localizer_control_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(ERROR, "Failed to reset localizer.\n");
}
}
@@ -311,7 +313,8 @@
localizer_control_builder.add_y(-3.4);
localizer_control_builder.add_keep_current_theta(true);
- if (!builder.Send(localizer_control_builder.Finish())) {
+ if (builder.Send(localizer_control_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(ERROR, "Failed to reset localizer.\n");
}
}
@@ -325,7 +328,8 @@
localizer_control_builder.add_y(3.4);
localizer_control_builder.add_theta(0.0);
- if (!builder.Send(localizer_control_builder.Finish())) {
+ if (builder.Send(localizer_control_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(ERROR, "Failed to reset localizer.\n");
}
}
@@ -339,7 +343,8 @@
localizer_control_builder.add_y(3.4);
localizer_control_builder.add_theta(M_PI);
- if (!builder.Send(localizer_control_builder.Finish())) {
+ if (builder.Send(localizer_control_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(ERROR, "Failed to reset localizer.\n");
}
}
@@ -353,7 +358,8 @@
localizer_control_builder.add_y(-3.4);
localizer_control_builder.add_theta(0.0);
- if (!builder.Send(localizer_control_builder.Finish())) {
+ if (builder.Send(localizer_control_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(ERROR, "Failed to reset localizer.\n");
}
}
@@ -367,7 +373,8 @@
localizer_control_builder.add_y(-3.4);
localizer_control_builder.add_theta(M_PI);
- if (!builder.Send(localizer_control_builder.Finish())) {
+ if (builder.Send(localizer_control_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(ERROR, "Failed to reset localizer.\n");
}
}
@@ -599,7 +606,8 @@
mutable_superstructure_goal->mutable_wrist()->mutate_unsafe_goal(
elevator_wrist_pos_.wrist);
- if (!main_superstructure_goal_builder.Send(superstructure_goal_offset)) {
+ if (main_superstructure_goal_builder.Send(superstructure_goal_offset) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(ERROR, "Sending superstructure goal failed.\n");
}
@@ -611,7 +619,8 @@
{
auto builder = camera_log_sender_.MakeBuilder();
- builder.Send(CreateCameraLog(*builder.fbb(), data.IsPressed(kCameraLog)));
+ (void)builder.Send(
+ CreateCameraLog(*builder.fbb(), data.IsPressed(kCameraLog)));
}
}
diff --git a/y2019/wpilib_interface.cc b/y2019/wpilib_interface.cc
index 885bc12..da076f2 100644
--- a/y2019/wpilib_interface.cc
+++ b/y2019/wpilib_interface.cc
@@ -247,7 +247,7 @@
drivetrain_builder.add_right_speed(-drivetrain_velocity_translate(
drivetrain_right_encoder_->GetPeriod()));
- builder.Send(drivetrain_builder.Finish());
+ builder.CheckOk(builder.Send(drivetrain_builder.Finish()));
}
const auto values = constants::GetValues();
@@ -308,7 +308,7 @@
position_builder.add_platform_right_detect(
!platform_right_detect_->Get());
- builder.Send(position_builder.Finish());
+ builder.CheckOk(builder.Send(position_builder.Finish()));
}
{
@@ -326,7 +326,7 @@
auto_mode_builder.add_mode(mode);
- builder.Send(auto_mode_builder.Finish());
+ builder.CheckOk(builder.Send(auto_mode_builder.Finish()));
}
}
@@ -457,7 +457,7 @@
.time_since_epoch())
.count());
camera_frame_builder.add_camera(received.camera_index);
- builder.Send(camera_frame_builder.Finish());
+ builder.CheckOk(builder.Send(camera_frame_builder.Finish()));
}
if (dummy_spi_) {
@@ -652,7 +652,7 @@
pcm_.Flush();
to_log_builder.add_read_solenoids(pcm_.GetAll());
- builder.Send(to_log_builder.Finish());
+ (void)builder.Send(to_log_builder.Finish());
}
status_light_fetcher_.Fetch();
diff --git a/y2020/actors/autonomous_actor.cc b/y2020/actors/autonomous_actor.cc
index c8f1ebe..eb8ea42 100644
--- a/y2020/actors/autonomous_actor.cc
+++ b/y2020/actors/autonomous_actor.cc
@@ -189,7 +189,8 @@
localizer_control_builder.add_theta_uncertainty(0.00001);
LOG(INFO) << "User button pressed, x: " << start(0) << " y: " << start(1)
<< " theta: " << start(2);
- if (!builder.Send(localizer_control_builder.Finish())) {
+ if (builder.Send(localizer_control_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(ERROR, "Failed to reset localizer.\n");
}
}
@@ -368,7 +369,8 @@
superstructure_builder.add_shooter_tracking(shooter_tracking_);
superstructure_builder.add_shooting(shooting_);
- if (!builder.Send(superstructure_builder.Finish())) {
+ if (builder.Send(superstructure_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(ERROR, "Sending superstructure goal failed.\n");
}
}
diff --git a/y2020/actors/shooter_tuning_actor.cc b/y2020/actors/shooter_tuning_actor.cc
index fac55c6..a6c8d88 100644
--- a/y2020/actors/shooter_tuning_actor.cc
+++ b/y2020/actors/shooter_tuning_actor.cc
@@ -163,7 +163,8 @@
superstructure_builder.add_shooter(shooter_offset);
superstructure_builder.add_shooting(shooting_);
- if (!builder.Send(superstructure_builder.Finish())) {
+ if (builder.Send(superstructure_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(ERROR, "Sending superstructure goal failed.\n");
}
}
diff --git a/y2020/control_loops/drivetrain/localizer.cc b/y2020/control_loops/drivetrain/localizer.cc
index d4d5f72..505a598 100644
--- a/y2020/control_loops/drivetrain/localizer.cc
+++ b/y2020/control_loops/drivetrain/localizer.cc
@@ -199,7 +199,7 @@
builder.MakeBuilder<LocalizerDebug>();
debug_builder.add_matches(vector_offset);
debug_builder.add_statistics(stats_offset);
- CHECK(builder.Send(debug_builder.Finish()));
+ builder.CheckOk(builder.Send(debug_builder.Finish()));
}
}
@@ -303,7 +303,8 @@
ImageMatchDebug::Builder builder(*fbb);
builder.add_camera(camera_index);
builder.add_pose_index(index);
- builder.add_local_image_capture_time_ns(result.image_monotonic_timestamp_ns());
+ builder.add_local_image_capture_time_ns(
+ result.image_monotonic_timestamp_ns());
builder.add_roborio_image_capture_time_ns(
capture_time.time_since_epoch().count());
builder.add_image_age_sec(aos::time::DurationInSeconds(now - capture_time));
@@ -390,8 +391,8 @@
(2.0 * dt_config_.robot_radius) +
(is_turret ? turret_data.velocity : 0.0));
- // Pay less attention to cameras that aren't actually on the turret, since they
- // are less useful when it comes to actually making shots.
+ // Pay less attention to cameras that aren't actually on the turret, since
+ // they are less useful when it comes to actually making shots.
if (!is_turret) {
noises *= 3.0;
} else {
diff --git a/y2020/control_loops/drivetrain/localizer_plotter.ts b/y2020/control_loops/drivetrain/localizer_plotter.ts
index e6729dd..86465a5 100644
--- a/y2020/control_loops/drivetrain/localizer_plotter.ts
+++ b/y2020/control_loops/drivetrain/localizer_plotter.ts
@@ -12,8 +12,6 @@
import Schema = configuration.reflection.Schema;
const TIME = AosPlotter.TIME;
-const DEFAULT_WIDTH = AosPlotter.DEFAULT_WIDTH;
-const DEFAULT_HEIGHT = AosPlotter.DEFAULT_HEIGHT;
export function plotLocalizer(conn: Connection, element: Element) : void {
@@ -27,11 +25,7 @@
const superstructureStatus = aosPlotter.addMessageSource(
'/superstructure', 'y2020.control_loops.superstructure.Status');
- var currentTop = 0;
-
- const imageAcceptedPlot = aosPlotter.addPlot(
- element, [0, currentTop], [DEFAULT_WIDTH, DEFAULT_HEIGHT]);
- currentTop += DEFAULT_HEIGHT;
+ const imageAcceptedPlot = aosPlotter.addPlot(element);
imageAcceptedPlot.plot.getAxisLabels().setTitle('Image Acceptance');
imageAcceptedPlot.plot.getAxisLabels().setXLabel(TIME);
imageAcceptedPlot.plot.getAxisLabels().setYLabel('[bool]');
@@ -41,9 +35,7 @@
.setColor(RED)
.setDrawLine(false);
- const impliedXPlot = aosPlotter.addPlot(
- element, [0, currentTop], [DEFAULT_WIDTH, DEFAULT_HEIGHT]);
- currentTop += DEFAULT_HEIGHT;
+ const impliedXPlot = aosPlotter.addPlot(element);
impliedXPlot.plot.getAxisLabels().setTitle('Implied Robot X');
impliedXPlot.plot.getAxisLabels().setXLabel(TIME);
impliedXPlot.plot.getAxisLabels().setYLabel('[m]');
@@ -58,9 +50,7 @@
.setColor(GREEN)
.setLabel('Localizer X');
- const impliedYPlot = aosPlotter.addPlot(
- element, [0, currentTop], [DEFAULT_WIDTH, DEFAULT_HEIGHT]);
- currentTop += DEFAULT_HEIGHT;
+ const impliedYPlot = aosPlotter.addPlot(element);
impliedYPlot.plot.getAxisLabels().setTitle('Implied Robot Y');
impliedYPlot.plot.getAxisLabels().setXLabel(TIME);
impliedYPlot.plot.getAxisLabels().setYLabel('[m]');
@@ -75,9 +65,7 @@
.setColor(GREEN)
.setLabel('Localizer Y');
- const impliedHeadingPlot = aosPlotter.addPlot(
- element, [0, currentTop], [DEFAULT_WIDTH, DEFAULT_HEIGHT]);
- currentTop += DEFAULT_HEIGHT;
+ const impliedHeadingPlot = aosPlotter.addPlot(element);
impliedHeadingPlot.plot.getAxisLabels().setTitle('Implied Robot Theta');
impliedHeadingPlot.plot.getAxisLabels().setXLabel(TIME);
impliedHeadingPlot.plot.getAxisLabels().setYLabel('[rad]');
@@ -89,9 +77,7 @@
.setColor(GREEN)
.setLabel('Localizer Theta');
- const impliedTurretGoalPlot = aosPlotter.addPlot(
- element, [0, currentTop], [DEFAULT_WIDTH, DEFAULT_HEIGHT]);
- currentTop += DEFAULT_HEIGHT;
+ const impliedTurretGoalPlot = aosPlotter.addPlot(element);
impliedTurretGoalPlot.plot.getAxisLabels().setTitle('Implied Turret Goal');
impliedTurretGoalPlot.plot.getAxisLabels().setXLabel(TIME);
impliedTurretGoalPlot.plot.getAxisLabels().setYLabel('[rad]');
@@ -102,9 +88,7 @@
impliedTurretGoalPlot.addMessageLine(superstructureStatus, ['aimer', 'turret_position'])
.setColor(GREEN);
- const imageTimingPlot = aosPlotter.addPlot(
- element, [0, currentTop], [DEFAULT_WIDTH, DEFAULT_HEIGHT]);
- currentTop += DEFAULT_HEIGHT;
+ const imageTimingPlot = aosPlotter.addPlot(element);
imageTimingPlot.plot.getAxisLabels().setTitle('Timing Plot');
imageTimingPlot.plot.getAxisLabels().setXLabel(TIME);
imageTimingPlot.plot.getAxisLabels().setYLabel('[ns]');
diff --git a/y2020/control_loops/drivetrain/localizer_test.cc b/y2020/control_loops/drivetrain/localizer_test.cc
index 8ccb55c..18df813 100644
--- a/y2020/control_loops/drivetrain/localizer_test.cc
+++ b/y2020/control_loops/drivetrain/localizer_test.cc
@@ -192,7 +192,8 @@
auto statistics_builder =
builder.MakeBuilder<aos::message_bridge::ServerStatistics>();
statistics_builder.add_connections(connections_offset);
- builder.Send(statistics_builder.Finish());
+ CHECK_EQ(builder.Send(statistics_builder.Finish()),
+ aos::RawSender::Error::kOk);
},
chrono::milliseconds(500));
@@ -210,7 +211,8 @@
auto turret_offset = turret_builder.Finish();
auto status_builder = builder.MakeBuilder<superstructure::Status>();
status_builder.add_turret(turret_offset);
- builder.Send(status_builder.Finish());
+ CHECK_EQ(builder.Send(status_builder.Finish()),
+ aos::RawSender::Error::kOk);
},
chrono::milliseconds(5));
@@ -341,8 +343,10 @@
std::get<0>(camera_delay_queue_.front()) <
monotonic_now() - camera_latency) {
auto builder = camera_sender_.MakeBuilder();
- ASSERT_TRUE(builder.Send(ImageMatchResult::Pack(
- *builder.fbb(), std::get<1>(camera_delay_queue_.front()).get())));
+ ASSERT_EQ(
+ builder.Send(ImageMatchResult::Pack(
+ *builder.fbb(), std::get<1>(camera_delay_queue_.front()).get())),
+ aos::RawSender::Error::kOk);
camera_delay_queue_.pop();
}
}
@@ -402,7 +406,8 @@
drivetrain_builder.add_left_goal(left);
drivetrain_builder.add_right_goal(right);
- EXPECT_TRUE(builder.Send(drivetrain_builder.Finish()));
+ EXPECT_EQ(builder.Send(drivetrain_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
private:
@@ -608,8 +613,8 @@
[this](int) {
auto builder = camera_sender_.MakeBuilder();
ImageMatchResultT image;
- ASSERT_TRUE(
- builder.Send(ImageMatchResult::Pack(*builder.fbb(), &image)));
+ ASSERT_EQ(builder.Send(ImageMatchResult::Pack(*builder.fbb(), &image)),
+ aos::RawSender::Error::kOk);
},
std::chrono::milliseconds(40));
test_event_loop_
diff --git a/y2020/control_loops/superstructure/accelerator_plotter.ts b/y2020/control_loops/superstructure/accelerator_plotter.ts
index b625a1c..e1bc5bc 100644
--- a/y2020/control_loops/superstructure/accelerator_plotter.ts
+++ b/y2020/control_loops/superstructure/accelerator_plotter.ts
@@ -21,8 +21,7 @@
// Robot Enabled/Disabled and Mode
const velocityPlot =
- aosPlotter.addPlot(element, [0, currentTop], [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
- currentTop += DEFAULT_HEIGHT / 2;
+ aosPlotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
velocityPlot.plot.getAxisLabels().setTitle('Velocity');
velocityPlot.plot.getAxisLabels().setXLabel(TIME);
velocityPlot.plot.getAxisLabels().setYLabel('rad/s');
@@ -38,8 +37,7 @@
velocityPlot.addMessageLine(status, ['shooter', 'accelerator_right', 'dt_angular_velocity']).setColor(BLUE).setPointSize(0.0);
const voltagePlot =
- aosPlotter.addPlot(element, [0, currentTop], [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
- currentTop += DEFAULT_HEIGHT / 2;
+ aosPlotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
voltagePlot.plot.getAxisLabels().setTitle('Voltage');
voltagePlot.plot.getAxisLabels().setXLabel(TIME);
voltagePlot.plot.getAxisLabels().setYLabel('Volts');
@@ -53,8 +51,7 @@
const currentPlot =
- aosPlotter.addPlot(element, [0, currentTop], [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
- currentTop += DEFAULT_HEIGHT / 2;
+ aosPlotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
currentPlot.plot.getAxisLabels().setTitle('Current');
currentPlot.plot.getAxisLabels().setXLabel(TIME);
currentPlot.plot.getAxisLabels().setYLabel('Amps');
diff --git a/y2020/control_loops/superstructure/finisher_plotter.ts b/y2020/control_loops/superstructure/finisher_plotter.ts
index c9420ae..474c8a4 100644
--- a/y2020/control_loops/superstructure/finisher_plotter.ts
+++ b/y2020/control_loops/superstructure/finisher_plotter.ts
@@ -17,12 +17,9 @@
const pdpValues = aosPlotter.addMessageSource('/roborio/aos', 'frc971.PDPValues');
const robotState = aosPlotter.addMessageSource('/aos', 'aos.RobotState');
- var currentTop = 0;
-
// Robot Enabled/Disabled and Mode
const velocityPlot =
- aosPlotter.addPlot(element, [0, currentTop], [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
- currentTop += DEFAULT_HEIGHT / 2;
+ aosPlotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
velocityPlot.plot.getAxisLabels().setTitle('Velocity');
velocityPlot.plot.getAxisLabels().setXLabel(TIME);
velocityPlot.plot.getAxisLabels().setYLabel('rad/s');
@@ -35,8 +32,7 @@
velocityPlot.addMessageLine(status, ['shooter', 'finisher', 'dt_angular_velocity']).setColor(PINK).setPointSize(0.0);
const ballsShotPlot =
- aosPlotter.addPlot(element, [0, currentTop], [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
- currentTop += DEFAULT_HEIGHT / 2;
+ aosPlotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
ballsShotPlot.plot.getAxisLabels().setTitle('Balls Shot');
ballsShotPlot.plot.getAxisLabels().setXLabel(TIME);
ballsShotPlot.plot.getAxisLabels().setYLabel('Balls');
@@ -45,8 +41,7 @@
const voltagePlot =
- aosPlotter.addPlot(element, [0, currentTop], [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
- currentTop += DEFAULT_HEIGHT / 2;
+ aosPlotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
voltagePlot.plot.getAxisLabels().setTitle('Voltage');
voltagePlot.plot.getAxisLabels().setXLabel(TIME);
voltagePlot.plot.getAxisLabels().setYLabel('Volts');
@@ -58,8 +53,7 @@
const currentPlot =
- aosPlotter.addPlot(element, [0, currentTop], [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
- currentTop += DEFAULT_HEIGHT / 2;
+ aosPlotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
currentPlot.plot.getAxisLabels().setTitle('Current');
currentPlot.plot.getAxisLabels().setXLabel(TIME);
currentPlot.plot.getAxisLabels().setYLabel('Amps');
diff --git a/y2020/control_loops/superstructure/hood_plotter.ts b/y2020/control_loops/superstructure/hood_plotter.ts
index 6c8025d..55b1ba8 100644
--- a/y2020/control_loops/superstructure/hood_plotter.ts
+++ b/y2020/control_loops/superstructure/hood_plotter.ts
@@ -20,7 +20,7 @@
// Robot Enabled/Disabled and Mode
const positionPlot =
- aosPlotter.addPlot(element, [0, currentTop], [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
+ aosPlotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
currentTop += DEFAULT_HEIGHT / 2;
positionPlot.plot.getAxisLabels().setTitle('Position');
positionPlot.plot.getAxisLabels().setXLabel(TIME);
@@ -35,7 +35,7 @@
positionPlot.addMessageLine(status, ['hood', 'estimator_state', 'position']).setColor(CYAN).setPointSize(0.0);
const voltagePlot =
- aosPlotter.addPlot(element, [0, currentTop], [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
+ aosPlotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
currentTop += DEFAULT_HEIGHT / 2;
voltagePlot.plot.getAxisLabels().setTitle('Voltage');
voltagePlot.plot.getAxisLabels().setXLabel(TIME);
diff --git a/y2020/control_loops/superstructure/shooter/flywheel_controller.cc b/y2020/control_loops/superstructure/shooter/flywheel_controller.cc
index 1fb943f..a25ed53 100644
--- a/y2020/control_loops/superstructure/shooter/flywheel_controller.cc
+++ b/y2020/control_loops/superstructure/shooter/flywheel_controller.cc
@@ -42,7 +42,7 @@
const double a = 1;
const double b = -bemf_voltage;
const double c_positive = -70.0 * 12.0 * resistance_;
- const double c_negative = -40.0 * 12.0 * resistance_;
+ const double c_negative = -25.0 * 12.0 * resistance_;
// Root is always positive.
const double root_positive = std::sqrt(b * b - 4.0 * a * c_positive);
@@ -52,8 +52,8 @@
// Limit to the battery voltage and the current limit voltage.
mutable_U(0, 0) = std::clamp(U(0, 0), lower_limit, upper_limit);
- if (R(0) > 50.0) {
- mutable_U(0, 0) = std::clamp(U(0, 0), -0.8, 12.0);
+ if (R(1) > 50.0) {
+ mutable_U(0, 0) = std::clamp(U(0, 0), 1.0, 12.0);
} else {
mutable_U(0, 0) = std::clamp(U(0, 0), 0.0, 12.0);
}
diff --git a/y2020/control_loops/superstructure/shooter/shooter_tuning_params_setter.cc b/y2020/control_loops/superstructure/shooter/shooter_tuning_params_setter.cc
index 3c6158e..68bb243 100644
--- a/y2020/control_loops/superstructure/shooter/shooter_tuning_params_setter.cc
+++ b/y2020/control_loops/superstructure/shooter/shooter_tuning_params_setter.cc
@@ -52,7 +52,7 @@
tuning_params_builder.add_finisher(finisher_params);
tuning_params_builder.add_accelerator(accelerator_params);
tuning_params_builder.add_balls_per_iteration(FLAGS_balls_per_iteration);
- CHECK(builder.Send(tuning_params_builder.Finish()));
+ builder.CheckOk(builder.Send(tuning_params_builder.Finish()));
return 0;
}
diff --git a/y2020/control_loops/superstructure/superstructure.cc b/y2020/control_loops/superstructure/superstructure.cc
index 2f07dc5..f70f107 100644
--- a/y2020/control_loops/superstructure/superstructure.cc
+++ b/y2020/control_loops/superstructure/superstructure.cc
@@ -81,9 +81,9 @@
CreateStaticZeroingSingleDOFProfiledSubsystemGoal(
*hood_goal.fbb(), shot_params.hood_angle));
- shooter_goal.Finish(CreateShooterGoal(
- *shooter_goal.fbb(), shot_params.velocity_accelerator,
- shot_params.velocity_finisher));
+ shooter_goal.Finish(CreateShooterGoal(*shooter_goal.fbb(),
+ shot_params.velocity_accelerator,
+ shot_params.velocity_finisher));
} else {
hood_goal.Finish(
frc971::control_loops::
@@ -242,7 +242,9 @@
status_builder.add_aimer(aimer_status_offset);
status_builder.add_subsystems_not_ready(subsystems_not_ready_offset);
- status->Send(status_builder.Finish());
+ status_builder.add_send_failures(status_failure_counter_.failures());
+
+ status_failure_counter_.Count(status->Send(status_builder.Finish()));
if (output != nullptr) {
output_struct.washing_machine_spinner_voltage = 0.0;
@@ -282,6 +284,12 @@
output_struct.feeder_voltage = -12.0;
}
+ if (unsafe_goal->has_feed_voltage_override()) {
+ output_struct.feeder_voltage = unsafe_goal->feed_voltage_override();
+ output_struct.washing_machine_spinner_voltage = -5.0;
+ preloading_timeout_ = position_timestamp;
+ }
+
if (unsafe_goal->shooting()) {
if ((shooter_.ready() ||
(!has_turret_ && shooter_.accelerator_ready())) &&
@@ -302,7 +310,7 @@
}
}
- output->Send(Output::Pack(*output->fbb(), &output_struct));
+ output->CheckOk(output->Send(Output::Pack(*output->fbb(), &output_struct)));
}
}
diff --git a/y2020/control_loops/superstructure/superstructure.h b/y2020/control_loops/superstructure/superstructure.h
index 7f565cf..5d371fc 100644
--- a/y2020/control_loops/superstructure/superstructure.h
+++ b/y2020/control_loops/superstructure/superstructure.h
@@ -80,6 +80,8 @@
bool has_turret_ = true;
+ aos::SendFailureCounter status_failure_counter_;
+
DISALLOW_COPY_AND_ASSIGN(Superstructure);
};
diff --git a/y2020/control_loops/superstructure/superstructure_goal.fbs b/y2020/control_loops/superstructure/superstructure_goal.fbs
index 990234a..f2b9096 100644
--- a/y2020/control_loops/superstructure/superstructure_goal.fbs
+++ b/y2020/control_loops/superstructure/superstructure_goal.fbs
@@ -55,6 +55,9 @@
// Positive is deploying climber and to climb; cannot run in reverse
climber_voltage:float (id: 10);
+
+ // Feed voltage override.
+ feed_voltage_override:float (id: 13);
}
root_type Goal;
diff --git a/y2020/control_loops/superstructure/superstructure_lib_test.cc b/y2020/control_loops/superstructure/superstructure_lib_test.cc
index 0e51b7b..e41c421 100644
--- a/y2020/control_loops/superstructure/superstructure_lib_test.cc
+++ b/y2020/control_loops/superstructure/superstructure_lib_test.cc
@@ -10,6 +10,7 @@
#include "frc971/control_loops/control_loop_test.h"
#include "frc971/control_loops/position_sensor_sim.h"
#include "frc971/control_loops/team_number_test_environment.h"
+#include "glog/logging.h"
#include "gtest/gtest.h"
#include "y2020/constants.h"
#include "y2020/control_loops/superstructure/accelerator/accelerator_plant.h"
@@ -207,7 +208,8 @@
position_builder.add_intake_beambreak_triggered(
intake_beambreak_triggered_);
- builder.Send(position_builder.Finish());
+ CHECK_EQ(builder.Send(position_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
double hood_position() const { return hood_plant_->X(0, 0); }
@@ -571,7 +573,8 @@
goal_builder.add_roller_voltage(roller_voltage);
goal_builder.add_roller_speed_compensation(roller_speed_compensation);
goal_builder.add_shooting(shooting);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(1));
superstructure_output_fetcher_.Fetch();
@@ -590,7 +593,7 @@
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_shooter(shooter_goal_offset);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ builder.CheckOk(builder.Send(goal_builder.Finish()));
},
dt());
}
@@ -683,7 +686,8 @@
goal_builder.add_turret(turret_offset);
goal_builder.add_shooter(shooter_offset);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(10));
VerifyNearGoal();
@@ -729,7 +733,8 @@
goal_builder.add_turret(turret_offset);
goal_builder.add_shooter(shooter_offset);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
// Give it a lot of time to get there.
@@ -770,7 +775,8 @@
goal_builder.add_turret(turret_offset);
goal_builder.add_shooter(shooter_offset);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(8));
VerifyNearGoal();
@@ -804,7 +810,8 @@
goal_builder.add_turret(turret_offset);
goal_builder.add_shooter(shooter_offset);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
superstructure_plant_.set_peak_hood_velocity(23.0);
// 30 hz sin wave on the hood causes acceleration to be ignored.
@@ -858,7 +865,8 @@
goal_builder.add_shooter(shooter_offset);
goal_builder.add_shooting(true);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
// In the beginning, the finisher and accelerator should not be ready
@@ -903,7 +911,8 @@
goal_builder.add_intake(intake_offset);
goal_builder.add_shooter(shooter_offset);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
// Give it a lot of time to get there.
@@ -952,7 +961,8 @@
goal_builder.add_climber_voltage(-10.0);
goal_builder.add_turret(turret_offset);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
// The turret needs to move out of the way first. This takes some time.
@@ -976,7 +986,8 @@
goal_builder.add_climber_voltage(10.0);
goal_builder.add_turret(turret_offset);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(1));
@@ -999,7 +1010,7 @@
goal_builder.add_intake_preloading(true);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ builder.CheckOk(builder.Send(goal_builder.Finish()));
}
superstructure_plant_.set_intake_beambreak_triggered(false);
@@ -1233,7 +1244,7 @@
std::sin(kShotAngle) * kShotDistance);
drivetrain_status_builder.add_localizer(localizer_offset);
- ASSERT_TRUE(builder.Send(drivetrain_status_builder.Finish()));
+ builder.CheckOk(builder.Send(drivetrain_status_builder.Finish()));
},
frc971::controls::kLoopFrequency);
@@ -1255,7 +1266,8 @@
joystick_builder.add_alliance(GetParam());
- ASSERT_TRUE(builder.Send(joystick_builder.Finish()));
+ ASSERT_EQ(builder.Send(joystick_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
};
@@ -1277,7 +1289,8 @@
goal_builder.add_turret_tracking(true);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ ASSERT_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
{
@@ -1299,7 +1312,8 @@
status_builder.add_theta(0.0);
status_builder.add_localizer(localizer_offset);
- ASSERT_TRUE(builder.Send(status_builder.Finish()));
+ ASSERT_EQ(builder.Send(status_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
// Give it time to stabilize.
@@ -1333,7 +1347,8 @@
goal_builder.add_shooter(shooter_goal);
goal_builder.add_hood(hood_offset);
- builder.Send(goal_builder.Finish());
+ CHECK_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(10));
@@ -1381,7 +1396,8 @@
status_builder.add_theta(0.0);
status_builder.add_localizer(localizer_offset);
- ASSERT_TRUE(builder.Send(status_builder.Finish()));
+ ASSERT_EQ(builder.Send(status_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
{
auto builder = superstructure_goal_sender_.MakeBuilder();
@@ -1399,7 +1415,8 @@
goal_builder.add_shooter_tracking(true);
goal_builder.add_hood_tracking(true);
- builder.Send(goal_builder.Finish());
+ CHECK_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(10));
@@ -1450,7 +1467,8 @@
status_builder.add_theta(0.0);
status_builder.add_localizer(localizer_offset);
- ASSERT_TRUE(builder.Send(status_builder.Finish()));
+ ASSERT_EQ(builder.Send(status_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
{
auto builder = superstructure_goal_sender_.MakeBuilder();
@@ -1468,7 +1486,8 @@
goal_builder.add_shooter_tracking(true);
goal_builder.add_hood_tracking(true);
- builder.Send(goal_builder.Finish());
+ CHECK_EQ(builder.Send(goal_builder.Finish()),
+ aos::RawSender::Error::kOk);
}
RunFor(chrono::seconds(10));
diff --git a/y2020/control_loops/superstructure/superstructure_status.fbs b/y2020/control_loops/superstructure/superstructure_status.fbs
index 4a977b8..611661c 100644
--- a/y2020/control_loops/superstructure/superstructure_status.fbs
+++ b/y2020/control_loops/superstructure/superstructure_status.fbs
@@ -87,6 +87,9 @@
// Vector of the subsystems that are not at goal and are preventing shooting.
subsystems_not_ready:[Subsystem] (id: 8);
+
+ // Total number of status send failures.
+ send_failures:uint64 (id: 9);
}
root_type Status;
diff --git a/y2020/control_loops/superstructure/turret_plotter.ts b/y2020/control_loops/superstructure/turret_plotter.ts
index 948ca97..34279ba 100644
--- a/y2020/control_loops/superstructure/turret_plotter.ts
+++ b/y2020/control_loops/superstructure/turret_plotter.ts
@@ -12,8 +12,6 @@
import Schema = configuration.reflection.Schema;
const TIME = AosPlotter.TIME;
-const DEFAULT_WIDTH = AosPlotter.DEFAULT_WIDTH;
-const DEFAULT_HEIGHT = AosPlotter.DEFAULT_HEIGHT;
class DerivativeMessageHandler extends MessageHandler {
// Calculated magnitude of the measured acceleration from the IMU.
@@ -71,11 +69,7 @@
const localizerDebug =
aosPlotter.addMessageSource('/drivetrain', 'y2020.control_loops.drivetrain.LocalizerDebug');
- var currentTop = 0;
-
- const turretPosPlot = aosPlotter.addPlot(
- element, [0, currentTop], [DEFAULT_WIDTH, DEFAULT_HEIGHT]);
- currentTop += DEFAULT_HEIGHT;
+ const turretPosPlot = aosPlotter.addPlot(element);
turretPosPlot.plot.getAxisLabels().setTitle('Turret Position');
turretPosPlot.plot.getAxisLabels().setXLabel(TIME);
turretPosPlot.plot.getAxisLabels().setYLabel('rad');
@@ -93,9 +87,7 @@
.setColor(BLUE)
.setDrawLine(false);
- const turretVelPlot = aosPlotter.addPlot(
- element, [0, currentTop], [DEFAULT_WIDTH, DEFAULT_HEIGHT]);
- currentTop += DEFAULT_HEIGHT;
+ const turretVelPlot = aosPlotter.addPlot(element);
turretVelPlot.plot.getAxisLabels().setTitle('Turret Velocity');
turretVelPlot.plot.getAxisLabels().setXLabel(TIME);
turretVelPlot.plot.getAxisLabels().setYLabel('rad / sec');
@@ -110,9 +102,7 @@
.setColor(BLUE)
.setDrawLine(false);
- const turretAccelPlot = aosPlotter.addPlot(
- element, [0, currentTop], [DEFAULT_WIDTH, DEFAULT_HEIGHT]);
- currentTop += DEFAULT_HEIGHT;
+ const turretAccelPlot = aosPlotter.addPlot(element);
turretAccelPlot.plot.getAxisLabels().setTitle('Turret Acceleration');
turretAccelPlot.plot.getAxisLabels().setXLabel(TIME);
turretAccelPlot.plot.getAxisLabels().setYLabel('rad / sec / sec');
@@ -121,9 +111,7 @@
.setColor(RED)
.setPointSize(0.0);
- const turretVoltagePlot = aosPlotter.addPlot(
- element, [0, currentTop], [DEFAULT_WIDTH, DEFAULT_HEIGHT]);
- currentTop += DEFAULT_HEIGHT;
+ const turretVoltagePlot = aosPlotter.addPlot(element);
turretVoltagePlot.plot.getAxisLabels().setTitle('Turret Voltage');
turretVoltagePlot.plot.getAxisLabels().setXLabel(TIME);
turretVoltagePlot.plot.getAxisLabels().setYLabel('V');
@@ -141,9 +129,7 @@
.setColor(RED)
.setPointSize(0.0);
- const currentPlot = aosPlotter.addPlot(
- element, [0, currentTop], [DEFAULT_WIDTH, DEFAULT_HEIGHT]);
- currentTop += DEFAULT_HEIGHT;
+ const currentPlot = aosPlotter.addPlot(element);
currentPlot.plot.getAxisLabels().setTitle('Current');
currentPlot.plot.getAxisLabels().setXLabel(TIME);
currentPlot.plot.getAxisLabels().setYLabel('Amps');
@@ -154,9 +140,7 @@
.setPointSize(0.0);
- const targetDistancePlot = aosPlotter.addPlot(
- element, [0, currentTop], [DEFAULT_WIDTH, DEFAULT_HEIGHT]);
- currentTop += DEFAULT_HEIGHT;
+ const targetDistancePlot = aosPlotter.addPlot(element);
targetDistancePlot.plot.getAxisLabels().setTitle('Target distance');
targetDistancePlot.plot.getAxisLabels().setXLabel(TIME);
targetDistancePlot.plot.getAxisLabels().setYLabel('m');
@@ -165,9 +149,7 @@
.setColor(RED)
.setPointSize(0.0);
- const targetChoicePlot = aosPlotter.addPlot(
- element, [0, currentTop], [DEFAULT_WIDTH, DEFAULT_HEIGHT]);
- currentTop += DEFAULT_HEIGHT;
+ const targetChoicePlot = aosPlotter.addPlot(element);
targetChoicePlot.plot.getAxisLabels().setTitle('Target choice');
targetChoicePlot.plot.getAxisLabels().setXLabel(TIME);
targetChoicePlot.plot.getAxisLabels().setYLabel('[bool]');
@@ -177,9 +159,7 @@
.setColor(RED)
.setPointSize(0.0);
- const imageAcceptedPlot = aosPlotter.addPlot(
- element, [0, currentTop], [DEFAULT_WIDTH, DEFAULT_HEIGHT]);
- currentTop += DEFAULT_HEIGHT;
+ const imageAcceptedPlot = aosPlotter.addPlot(element);
imageAcceptedPlot.plot.getAxisLabels().setTitle('Image Acceptance');
imageAcceptedPlot.plot.getAxisLabels().setXLabel(TIME);
imageAcceptedPlot.plot.getAxisLabels().setYLabel('[bool]');
diff --git a/y2020/joystick_reader.cc b/y2020/joystick_reader.cc
index dd98e63..b610b64 100644
--- a/y2020/joystick_reader.cc
+++ b/y2020/joystick_reader.cc
@@ -87,7 +87,8 @@
localizer_control_builder.add_theta_uncertainty(10.0);
localizer_control_builder.add_theta(0.0);
localizer_control_builder.add_keep_current_theta(false);
- if (!builder.Send(localizer_control_builder.Finish())) {
+ if (builder.Send(localizer_control_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(ERROR, "Failed to reset blue localizer.\n");
}
}
@@ -103,7 +104,8 @@
localizer_control_builder.add_theta_uncertainty(10.0);
localizer_control_builder.add_theta(M_PI);
localizer_control_builder.add_keep_current_theta(false);
- if (!builder.Send(localizer_control_builder.Finish())) {
+ if (builder.Send(localizer_control_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(ERROR, "Failed to reset red localizer.\n");
}
}
@@ -129,7 +131,8 @@
frc971::zeroing::Wrap(drivetrain_status->theta(), 0, M_PI);
localizer_control_builder.add_theta(new_theta);
localizer_control_builder.add_theta_uncertainty(10.0);
- if (!builder.Send(localizer_control_builder.Finish())) {
+ if (builder.Send(localizer_control_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(ERROR, "Failed to reset localizer.\n");
}
}
@@ -292,6 +295,9 @@
superstructure_goal_builder.add_shooter(shooter_offset);
superstructure_goal_builder.add_shooting(data.IsPressed(kFeed) ||
data.IsPressed(kFeedDriver));
+ if (data.IsPressed(kSpit)) {
+ superstructure_goal_builder.add_feed_voltage_override(-7.0);
+ }
superstructure_goal_builder.add_climber_voltage(climber_speed);
superstructure_goal_builder.add_turret_tracking(turret_tracking);
@@ -303,7 +309,8 @@
data.IsPressed(kFeedDriver)));
superstructure_goal_builder.add_intake_preloading(preload_intake);
- if (!builder.Send(superstructure_goal_builder.Finish())) {
+ if (builder.Send(superstructure_goal_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
AOS_LOG(ERROR, "Sending superstructure goal failed.\n");
}
}
diff --git a/y2020/setpoint_setter.cc b/y2020/setpoint_setter.cc
index 1e1a7b8..e04fe41 100644
--- a/y2020/setpoint_setter.cc
+++ b/y2020/setpoint_setter.cc
@@ -1,6 +1,7 @@
#include "aos/events/shm_event_loop.h"
#include "aos/init.h"
#include "gflags/gflags.h"
+#include "glog/logging.h"
#include "y2020/setpoint_generated.h"
DEFINE_double(accelerator, 250.0, "Accelerator speed");
@@ -29,7 +30,7 @@
setpoint_builder.add_finisher(FLAGS_finisher);
setpoint_builder.add_hood(FLAGS_hood);
setpoint_builder.add_turret(FLAGS_turret);
- builder.Send(setpoint_builder.Finish());
+ builder.CheckOk(builder.Send(setpoint_builder.Finish()));
return 0;
}
diff --git a/y2020/vision/camera_reader.cc b/y2020/vision/camera_reader.cc
index e908a47..b13c19c 100644
--- a/y2020/vision/camera_reader.cc
+++ b/y2020/vision/camera_reader.cc
@@ -165,6 +165,7 @@
std::vector<cv::FlannBasedMatcher> matchers_;
aos::Sender<CameraImage> image_sender_;
aos::Sender<sift::ImageMatchResult> result_sender_;
+ aos::SendFailureCounter result_failure_counter_;
aos::Sender<sift::ImageMatchResult> detailed_result_sender_;
// We schedule this immediately to read an image. Having it on a timer means
// other things can run on the event loop in between.
@@ -289,10 +290,11 @@
result_builder.add_image_monotonic_timestamp_ns(
image.monotonic_timestamp_ns());
result_builder.add_camera_calibration(camera_calibration_offset);
+ result_builder.add_send_failures(result_failure_counter_.failures());
// TODO<Jim>: Need to add target point computed from matches and
// mapped by homography
- builder.Send(result_builder.Finish());
+ result_failure_counter_.Count(builder.Send(result_builder.Finish()));
}
void CameraReader::ProcessImage(const CameraImage &image) {
@@ -713,7 +715,8 @@
{
aos::Sender<sift::TrainingData> training_data_sender =
event_loop.MakeSender<sift::TrainingData>("/camera");
- training_data_sender.Send(training_data);
+ CHECK_EQ(training_data_sender.Send(training_data),
+ aos::RawSender::Error::kOk);
}
V4L2Reader v4l2_reader(&event_loop, "/dev/video0");
diff --git a/y2020/vision/charuco_lib.cc b/y2020/vision/charuco_lib.cc
index 77e1ba9..856c560 100644
--- a/y2020/vision/charuco_lib.cc
+++ b/y2020/vision/charuco_lib.cc
@@ -102,13 +102,13 @@
const monotonic_clock::time_point eof_source_node =
monotonic_clock::time_point(
chrono::nanoseconds(image.monotonic_timestamp_ns()));
- server_fetcher_.Fetch();
- if (!server_fetcher_.get()) {
- return;
- }
-
chrono::nanoseconds offset{0};
if (source_node_ != event_loop_->node()) {
+ server_fetcher_.Fetch();
+ if (!server_fetcher_.get()) {
+ return;
+ }
+
// If we are viewing this image from another node, convert to our
// monotonic clock.
const aos::message_bridge::ServerConnection *server_connection = nullptr;
diff --git a/y2020/vision/sift/BUILD b/y2020/vision/sift/BUILD
index 98c6ec6..93e2858 100644
--- a/y2020/vision/sift/BUILD
+++ b/y2020/vision/sift/BUILD
@@ -25,8 +25,6 @@
"@amd64_debian_sysroot//:sysroot_files",
],
main = "fast_gaussian_runner.py",
- python_version = "PY3",
- srcs_version = "PY2AND3",
target_compatible_with = ["@platforms//os:linux"],
toolchains = [
"@bazel_tools//tools/cpp:current_cc_toolchain",
@@ -220,8 +218,6 @@
py_binary(
name = "demo_sift_training",
srcs = ["demo_sift_training.py"],
- python_version = "PY3",
- srcs_version = "PY2AND3",
target_compatible_with = ["@platforms//os:linux"],
deps = [
":sift_fbs_python",
diff --git a/y2020/vision/sift/sift.fbs b/y2020/vision/sift/sift.fbs
index 427b91c..3336d0c 100644
--- a/y2020/vision/sift/sift.fbs
+++ b/y2020/vision/sift/sift.fbs
@@ -167,6 +167,9 @@
// Information about the camera which took this image.
camera_calibration:CameraCalibration (id: 4);
+
+ // Total number of match result send failures.
+ send_failures:uint64 (id: 5);
}
root_type ImageMatchResult;
diff --git a/y2020/vision/tools/python_code/BUILD b/y2020/vision/tools/python_code/BUILD
index fc7322d..7579a75 100644
--- a/y2020/vision/tools/python_code/BUILD
+++ b/y2020/vision/tools/python_code/BUILD
@@ -4,12 +4,10 @@
py_library(
name = "train_and_match",
srcs = ["train_and_match.py"],
- data = [
- "@python_repo//:scipy",
- ],
deps = [
"//external:python-glog",
"@opencv_contrib_nonfree_amd64//:python_opencv",
+ "@python_repo//:scipy",
],
)
@@ -18,13 +16,11 @@
srcs = [
"define_training_data.py",
],
- data = [
- "@python_repo//:scipy",
- ],
deps = [
":train_and_match",
"//external:python-glog",
"@opencv_contrib_nonfree_amd64//:python_opencv",
+ "@python_repo//:scipy",
],
)
@@ -61,7 +57,6 @@
"test_images/*.png",
]),
main = "target_definition.py",
- python_version = "PY3",
target_compatible_with = ["@platforms//os:linux"],
deps = [
":target_definition",
@@ -80,7 +75,6 @@
data = glob(["calib_files/*.json"]) + glob([
"test_images/*.png",
]),
- python_version = "PY3",
target_compatible_with = ["@platforms//os:linux"],
deps = [
":camera_definition",
@@ -100,7 +94,6 @@
data = glob(["calib_files/*.json"]) + glob([
"test_images/*.png",
]),
- python_version = "PY3",
target_compatible_with = ["@platforms//os:linux"],
deps = [
":camera_definition",
@@ -156,8 +149,6 @@
"test_images/*.png",
]),
main = "load_sift_training.py",
- python_version = "PY3",
- srcs_version = "PY2AND3",
target_compatible_with = ["@platforms//os:linux"],
deps = [
":load_sift_training",
diff --git a/y2020/vision/v4l2_reader.h b/y2020/vision/v4l2_reader.h
index 3c9d795..04548d6 100644
--- a/y2020/vision/v4l2_reader.h
+++ b/y2020/vision/v4l2_reader.h
@@ -53,7 +53,7 @@
aos::monotonic_clock::time_point monotonic_eof);
void Send() {
- builder.Send(message_offset);
+ (void)builder.Send(message_offset);
message_offset = flatbuffers::Offset<CameraImage>();
}
diff --git a/y2020/wpilib_interface.cc b/y2020/wpilib_interface.cc
index 1b732bc..f746970 100644
--- a/y2020/wpilib_interface.cc
+++ b/y2020/wpilib_interface.cc
@@ -243,7 +243,7 @@
drivetrain_builder.add_right_speed(-drivetrain_velocity_translate(
drivetrain_right_encoder_->GetPeriod()));
- builder.Send(drivetrain_builder.Finish());
+ builder.CheckOk(builder.Send(drivetrain_builder.Finish()));
}
const constants::Values &values = constants::GetValues();
@@ -306,7 +306,7 @@
position_builder.add_intake_beambreak_triggered(
ball_intake_beambreak_->Get());
- builder.Send(position_builder.Finish());
+ builder.CheckOk(builder.Send(position_builder.Finish()));
}
{
@@ -324,7 +324,7 @@
auto_mode_builder.add_mode(mode);
- builder.Send(auto_mode_builder.Finish());
+ builder.CheckOk(builder.Send(auto_mode_builder.Finish()));
}
if (FLAGS_shooter_tuning) {
@@ -339,7 +339,7 @@
builder.MakeBuilder<superstructure::shooter::TuningReadings>();
shooter_tuning_readings_builder.add_velocity_ball(
kDistanceBetweenBeambreaks / ball_beambreak_reader_.last_width());
- builder.Send(shooter_tuning_readings_builder.Finish());
+ builder.CheckOk(builder.Send(shooter_tuning_readings_builder.Finish()));
}
}
}
@@ -625,7 +625,8 @@
std::unique_ptr<frc971::wpilib::ADIS16448> old_imu;
std::unique_ptr<frc971::wpilib::ADIS16470> new_imu;
std::unique_ptr<frc::SPI> imu_spi;
- if (::aos::network::GetTeamNumber() != constants::Values::kCodingRobotTeamNumber) {
+ if (::aos::network::GetTeamNumber() !=
+ constants::Values::kCodingRobotTeamNumber) {
old_imu = make_unique<frc971::wpilib::ADIS16448>(
&imu_event_loop, spi_port, imu_trigger.get());
old_imu->SetDummySPI(frc::SPI::Port::kOnboardCS2);
diff --git a/y2021_bot3/control_loops/superstructure/BUILD b/y2021_bot3/control_loops/superstructure/BUILD
index 77cdf45..e4dd6a2 100644
--- a/y2021_bot3/control_loops/superstructure/BUILD
+++ b/y2021_bot3/control_loops/superstructure/BUILD
@@ -1,6 +1,7 @@
package(default_visibility = ["//visibility:public"])
load("@com_github_google_flatbuffers//:build_defs.bzl", "flatbuffer_cc_library")
+load("@npm_bazel_typescript//:defs.bzl", "ts_library")
flatbuffer_cc_library(
name = "superstructure_goal_fbs",
@@ -101,4 +102,15 @@
"//frc971/control_loops:team_number_test_environment",
"//frc971/control_loops/drivetrain:drivetrain_status_fbs",
],
+)
+
+ts_library(
+ name = "superstructure_plotter",
+ srcs = ["superstructure_plotter.ts"],
+ target_compatible_with = ["@platforms//os:linux"],
+ deps = [
+ "//aos/network/www:aos_plotter",
+ "//aos/network/www:colors",
+ "//aos/network/www:proxy",
+ ],
)
\ No newline at end of file
diff --git a/y2021_bot3/control_loops/superstructure/superstructure.cc b/y2021_bot3/control_loops/superstructure/superstructure.cc
index fbedb22..1b4b611 100644
--- a/y2021_bot3/control_loops/superstructure/superstructure.cc
+++ b/y2021_bot3/control_loops/superstructure/superstructure.cc
@@ -33,7 +33,7 @@
std::clamp(unsafe_goal->outtake_speed(), -12.0, 12.0);
output_struct.climber_volts =
std::clamp(unsafe_goal->climber_speed(), -12.0, 12.0);
- output->Send(Output::Pack(*output->fbb(), &output_struct));
+ output->CheckOk(output->Send(Output::Pack(*output->fbb(), &output_struct)));
}
Status::Builder status_builder = status->MakeBuilder<Status>();
@@ -47,7 +47,7 @@
status_builder.add_climber_speed(unsafe_goal->climber_speed());
}
- status->Send(status_builder.Finish());
+ (void)status->Send(status_builder.Finish());
}
} // namespace superstructure
diff --git a/y2021_bot3/control_loops/superstructure/superstructure_lib_test.cc b/y2021_bot3/control_loops/superstructure/superstructure_lib_test.cc
index a6b6353..e30fa1d 100644
--- a/y2021_bot3/control_loops/superstructure/superstructure_lib_test.cc
+++ b/y2021_bot3/control_loops/superstructure/superstructure_lib_test.cc
@@ -1,13 +1,16 @@
#include <chrono>
#include <memory>
-#include "aos/events/logging/log_writer.h"
#include "frc971/control_loops/capped_test_plant.h"
#include "frc971/control_loops/control_loop_test.h"
#include "frc971/control_loops/position_sensor_sim.h"
#include "frc971/control_loops/team_number_test_environment.h"
#include "gtest/gtest.h"
#include "y2021_bot3/control_loops/superstructure/superstructure.h"
+#include "aos/events/logging/log_writer.h"
+
+DEFINE_string(output_folder, "",
+ "If set, logs all channels to the provided logfile.");
namespace y2021_bot3 {
namespace control_loops {
@@ -40,6 +43,13 @@
phased_loop_handle_ = test_event_loop_->AddPhasedLoop(
[this](int) { SendPositionMessage(); }, dt());
+
+ if (!FLAGS_output_folder.empty()) {
+ unlink(FLAGS_output_folder.c_str());
+ logger_event_loop_ = MakeEventLoop("logger", roborio_);
+ logger_ = std::make_unique<aos::logger::Logger>(logger_event_loop_.get());
+ logger_->StartLoggingLocalNamerOnRun(FLAGS_output_folder);
+ }
}
void VerifyResults(double intake_voltage, double outtake_voltage,
@@ -62,9 +72,12 @@
void SendPositionMessage() {
auto builder = superstructure_position_sender_.MakeBuilder();
Position::Builder position_builder = builder.MakeBuilder<Position>();
- builder.Send(position_builder.Finish());
+ builder.CheckOk(builder.Send(position_builder.Finish()));
}
+ // Because the third robot is single node, the roborio node is nullptr
+ const aos::Node *const roborio_ = nullptr;
+
::std::unique_ptr<::aos::EventLoop> superstructure_event_loop;
::y2021_bot3::control_loops::superstructure::Superstructure superstructure_;
::std::unique_ptr<::aos::EventLoop> test_event_loop_;
@@ -75,6 +88,8 @@
::aos::Fetcher<Output> superstructure_output_fetcher_;
::aos::Fetcher<Position> superstructure_position_fetcher_;
::aos::Sender<Position> superstructure_position_sender_;
+ std::unique_ptr<aos::EventLoop> logger_event_loop_;
+ std::unique_ptr<aos::logger::Logger> logger_;
};
// Tests running the intake and outtake separately
@@ -83,7 +98,7 @@
auto builder = superstructure_goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_intake_speed(10.0);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ builder.CheckOk(builder.Send(goal_builder.Finish()));
SendPositionMessage();
RunFor(dt() * 2);
VerifyResults(10.0, 0.0, 0.0, 10.0, 0.0, 0.0);
@@ -93,7 +108,7 @@
auto builder = superstructure_goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_outtake_speed(10.0);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ builder.CheckOk(builder.Send(goal_builder.Finish()));
RunFor(dt() * 2);
VerifyResults(0.0, 10.0, 0.0, 0.0, 10.0, 0.0);
}
@@ -103,7 +118,7 @@
auto builder = superstructure_goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_climber_speed(4.0);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ builder.CheckOk(builder.Send(goal_builder.Finish()));
RunFor(dt() * 2);
VerifyResults(0.0, 0.0, 4.0, 0.0, 0.0, 4.0);
}
@@ -114,7 +129,7 @@
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_intake_speed(10.0);
goal_builder.add_outtake_speed(5.0);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ builder.CheckOk(builder.Send(goal_builder.Finish()));
RunFor(dt() * 2);
VerifyResults(10.0, 5.0, 0.0, 10.0, 5.0, 0.0);
}
@@ -128,7 +143,7 @@
goal_builder.add_intake_speed(20.0);
goal_builder.add_outtake_speed(15.0);
goal_builder.add_climber_speed(18.0);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ builder.CheckOk(builder.Send(goal_builder.Finish()));
RunFor(dt() * 2);
VerifyResults(12.0, 12.0, 12.0, 20.0, 15.0, 18.0);
}
@@ -139,7 +154,7 @@
goal_builder.add_intake_speed(-20.0);
goal_builder.add_outtake_speed(-15.0);
goal_builder.add_climber_speed(-18.0);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ builder.CheckOk(builder.Send(goal_builder.Finish()));
RunFor(dt() * 2);
VerifyResults(-12.0, -12.0, -12.0, -20.0, -15.0, -18.0);
}
@@ -149,7 +164,7 @@
TEST_F(SuperstructureTest, GoalIsNull) {
auto builder = superstructure_goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ builder.CheckOk(builder.Send(goal_builder.Finish()));
RunFor(dt() * 2);
VerifyResults(0.0, 0.0, 0.0, 0.0, 0.0, 0.0);
}
@@ -161,13 +176,32 @@
goal_builder.add_intake_speed(6.0);
goal_builder.add_outtake_speed(5.0);
goal_builder.add_climber_speed(4.0);
- ASSERT_TRUE(builder.Send(goal_builder.Finish()));
+ builder.CheckOk(builder.Send(goal_builder.Finish()));
SetEnabled(false);
RunFor(dt() * 2);
VerifyResults(0.0, 0.0, 0.0, 6.0, 5.0, 4.0);
}
+TEST_F(SuperstructureTest, PlotterTest) {
+ double speed = 10.0;
+ test_event_loop_->AddPhasedLoop(
+ [&](int) {
+ auto builder = superstructure_goal_sender_.MakeBuilder();
+ Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
+ goal_builder.add_intake_speed(speed);
+ goal_builder.add_outtake_speed(speed);
+ goal_builder.add_climber_speed(speed);
+ builder.CheckOk(builder.Send(goal_builder.Finish()));
+ speed += .001;
+ if (speed >= 12) {
+ speed = -12;
+ }
+ },
+ frc971::controls::kLoopFrequency);
+ RunFor(std::chrono::seconds(10));
+}
+
} // namespace testing
} // namespace superstructure
} // namespace control_loops
-} // namespace y2021_bot3
\ No newline at end of file
+} // namespace y2021_bot3
diff --git a/y2021_bot3/control_loops/superstructure/superstructure_plotter.ts b/y2021_bot3/control_loops/superstructure/superstructure_plotter.ts
new file mode 100644
index 0000000..f453d64
--- /dev/null
+++ b/y2021_bot3/control_loops/superstructure/superstructure_plotter.ts
@@ -0,0 +1,41 @@
+// Provides a plot for debugging robot state-related issues.
+import {AosPlotter} from 'org_frc971/aos/network/www/aos_plotter';
+import * as proxy from 'org_frc971/aos/network/www/proxy';
+import {BLUE, BROWN, CYAN, GREEN, PINK, RED, WHITE} from 'org_frc971/aos/network/www/colors';
+
+import Connection = proxy.Connection;
+
+const TIME = AosPlotter.TIME;
+const DEFAULT_WIDTH = AosPlotter.DEFAULT_WIDTH;
+const DEFAULT_HEIGHT = AosPlotter.DEFAULT_HEIGHT * 3;
+
+export function plotSuperstructure(conn: Connection, element: Element) : void {
+ const aosPlotter = new AosPlotter(conn);
+ const goal = aosPlotter.addMessageSource('/superstructure', 'y2021_bot3.control_loops.superstructure.Goal');
+ const output = aosPlotter.addMessageSource('/superstructure', 'y2021_bot3.control_loops.superstructure.Output');
+ const status = aosPlotter.addMessageSource('/superstructure', 'y2021_bot3.control_loops.superstructure.Status');
+ const position = aosPlotter.addMessageSource('/superstructure', 'y2021_bot3.control_loops.superstructure.Position');
+ const robotState = aosPlotter.addMessageSource('/aos', 'aos.RobotState');
+
+ const intakePlot =
+ aosPlotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
+ intakePlot.plot.getAxisLabels().setTitle('Intake');
+ intakePlot.plot.getAxisLabels().setXLabel(TIME);
+ intakePlot.plot.getAxisLabels().setYLabel('Volts');
+ intakePlot.plot.setDefaultYRange([-20.0, 20.0]);
+
+ intakePlot.addMessageLine(output, ['intake_volts']).setColor(BLUE);
+ intakePlot.addMessageLine(goal, ['intake_speed']).setColor(GREEN);
+ intakePlot.addMessageLine(status, ['intake_speed']).setColor(RED);
+
+ const outtakePlot =
+ aosPlotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
+ outtakePlot.plot.getAxisLabels().setTitle('Outtake');
+ outtakePlot.plot.getAxisLabels().setXLabel(TIME);
+ outtakePlot.plot.getAxisLabels().setYLabel('Volts');
+ outtakePlot.plot.setDefaultYRange([-20.0, 20.0]);
+
+ outtakePlot.addMessageLine(output, ['outtake_volts']).setColor(BLUE);
+ outtakePlot.addMessageLine(goal, ['outtake_speed']).setColor(GREEN);
+ outtakePlot.addMessageLine(status, ['outtake_speed']).setColor(RED);
+}
diff --git a/y2021_bot3/wpilib_interface.cc b/y2021_bot3/wpilib_interface.cc
index 1808846..05a8895 100644
--- a/y2021_bot3/wpilib_interface.cc
+++ b/y2021_bot3/wpilib_interface.cc
@@ -148,14 +148,14 @@
drivetrain_builder.add_right_speed(-drivetrain_velocity_translate(
drivetrain_right_encoder_->GetPeriod()));
- builder.Send(drivetrain_builder.Finish());
+ builder.CheckOk(builder.Send(drivetrain_builder.Finish()));
}
{
auto builder = superstructure_position_sender_.MakeBuilder();
superstructure::Position::Builder position_builder =
builder.MakeBuilder<superstructure::Position>();
- builder.Send(position_builder.Finish());
+ builder.CheckOk(builder.Send(position_builder.Finish()));
}
{
@@ -173,7 +173,7 @@
auto_mode_builder.add_mode(mode);
- builder.Send(auto_mode_builder.Finish());
+ builder.CheckOk(builder.Send(auto_mode_builder.Finish()));
}
}