Skip to content

Commit

Permalink
Add redirection headers
Browse files Browse the repository at this point in the history
Signed-off-by: methylDragon <[email protected]>
  • Loading branch information
methylDragon committed Aug 19, 2022
1 parent 419502b commit 82bdd73
Show file tree
Hide file tree
Showing 212 changed files with 1,376 additions and 610 deletions.
4 changes: 3 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,9 @@ set(IGN_CMAKE_VER ${ignition-cmake2_VERSION_MAJOR})
#============================================================================
# Configure the project
#============================================================================
ign_configure_project()
ign_configure_project(
REPLACE_IGNITION_INCLUDE_PATH gz/transport
)

#============================================================================
# Set project-specific options
Expand Down
4 changes: 2 additions & 2 deletions Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -196,7 +196,7 @@

1. Added a `-n` argument to the echo command line tool, where `-n` can be used
to specify the number of messages to echo and then exit. Made the
`ign.hh` header file private (not installed).
`gz.hh` header file private (not installed).
* [BitBucket pull request 367](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-transport/pull-requests/367)

1. Added start of C interface, currently it supports only pub/sub.
Expand Down Expand Up @@ -371,7 +371,7 @@
1. Workaround for the ghost Msbuild warning in Jenkins plugin
* [BitBucket pull request 205](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-transport/pull-requests/205)

1. Added tests for ign.cc
1. Added tests for gz.cc
* [BitBucket pull request 209](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-transport/pull-requests/209)

1. Remove manual setting of flags for dynamic linking of the Windows CRT library
Expand Down
5 changes: 2 additions & 3 deletions Migration.md
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ release will remove the deprecated code.
1. NodeShared::TriggerSubscriberCallbacks
* [BitBucket pull request 404](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-transport/pull-requests/404)

1. The discovery wire protocol changed to use ignition::msgs::Discovery
1. The discovery wire protocol changed to use gz::msgs::Discovery
instead of C-structs. The Packet.hh header file is deprecated, which
contained the Header, SubscriptionMsg, and AdvertiseMessage classes. The
version of the wire protocal has bumped from 9 to 10. This means Ignition
Expand All @@ -24,7 +24,7 @@ release will remove the deprecated code.

### Removed

1. The `ign.hh` file is not longer installed.
1. The `gz.hh` file is not longer installed.
* [BitBucket pull request 367](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-transport/pull-requests/367)

## Ignition Transport 4.X to 5.X
Expand All @@ -36,4 +36,3 @@ release will remove the deprecated code.
functions have been deprecated.
* [BitBucket pull request 260](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-transport/pull-requests/260)
* [BitBucket pull request 228](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-transport/pull-requests/228)

46 changes: 23 additions & 23 deletions example/bench.cc
Original file line number Diff line number Diff line change
Expand Up @@ -86,12 +86,12 @@ class FloodSub

/// \brief Dummy callback.
/// \param[in] _msg The message.
public: void OnMsg(const ignition::msgs::Bytes & /*_msg*/)
public: void OnMsg(const gz::msgs::Bytes & /*_msg*/)
{
}

/// \brief Communication node.
private: ignition::transport::Node node;
private: gz::transport::Node node;
};

/// \brief A class that publishes on a number of `/benchmark/flood/*`
Expand All @@ -111,7 +111,7 @@ class FloodPub
std::ostringstream stream;
stream << "/benchmark/flood/" << i;
this->floodPubs.push_back(
this->node.Advertise<ignition::msgs::Bytes>(stream.str()));
this->node.Advertise<gz::msgs::Bytes>(stream.str()));
}
if (!this->floodPubs.empty())
this->runThread = std::thread(&FloodPub::RunLoop, this);
Expand All @@ -134,7 +134,7 @@ class FloodPub
/// \brief Run the publishers.
private: void RunLoop()
{
ignition::msgs::Bytes msg;
gz::msgs::Bytes msg;
int size = 1000;
char *byteData = new char[size];
std::memset(byteData, '0', size);
Expand All @@ -143,7 +143,7 @@ class FloodPub
this->running = true;
while (this->running)
{
for (ignition::transport::Node::Publisher &pub : this->floodPubs)
for (gz::transport::Node::Publisher &pub : this->floodPubs)
{
pub.Publish(msg);
}
Expand All @@ -152,7 +152,7 @@ class FloodPub
}

/// \brief Communication node.
private: ignition::transport::Node node;
private: gz::transport::Node node;

/// \brief Run thread.
private: std::thread runThread;
Expand All @@ -161,7 +161,7 @@ class FloodPub
private: bool running{false};

/// \brief The publishers.
private: std::vector<ignition::transport::Node::Publisher> floodPubs;
private: std::vector<gz::transport::Node::Publisher> floodPubs;
};

/// \brief The ReplyTester subscribes to the benchmark topics, and relays
Expand All @@ -172,14 +172,14 @@ class FloodPub
/// 1. /benchmark/latency/request For latency testing
/// 2. /benchmark/throughput/request For throughput testing.
///
/// The incoming and outgoing message types are ignition::msgs::Bytes.
/// The incoming and outgoing message types are gz::msgs::Bytes.
class ReplyTester
{
/// Constructor that creates the publishers and subscribers.
public: ReplyTester()
{
// Advertise on the throughput reply topic
this->throughputPub = this->node.Advertise<ignition::msgs::Bytes>(
this->throughputPub = this->node.Advertise<gz::msgs::Bytes>(
"/benchmark/throughput/reply");
if (!this->throughputPub)
{
Expand All @@ -189,7 +189,7 @@ class ReplyTester
}

// Advertise on the latency reply topic
this->latencyPub = this->node.Advertise<ignition::msgs::Bytes>(
this->latencyPub = this->node.Advertise<gz::msgs::Bytes>(
"/benchmark/latency/reply");
if (!this->latencyPub)
{
Expand Down Expand Up @@ -224,7 +224,7 @@ class ReplyTester

/// \brief Function called each time a throughput message is received.
/// \param[in] _msg Incoming message of variable size.
private: void ThroughputCb(const ignition::msgs::Bytes &_msg)
private: void ThroughputCb(const gz::msgs::Bytes &_msg)
{
if (this->prevStamp > 0 && _msg.header().stamp().sec() != 0)
{
Expand All @@ -245,19 +245,19 @@ class ReplyTester

/// \brief Function called each time a latency message is received.
/// \param[in] _msg Incoming message of variable size.
private: void LatencyCb(const ignition::msgs::Bytes &_msg)
private: void LatencyCb(const gz::msgs::Bytes &_msg)
{
this->latencyPub.Publish(_msg);
}

/// \brief The transport node
private: ignition::transport::Node node;
private: gz::transport::Node node;

/// \brief The throughput publisher
private: ignition::transport::Node::Publisher throughputPub;
private: gz::transport::Node::Publisher throughputPub;

/// \brief The latency publisher
private: ignition::transport::Node::Publisher latencyPub;
private: gz::transport::Node::Publisher latencyPub;

private: int prevStamp = 0;
};
Expand Down Expand Up @@ -304,7 +304,7 @@ class PubTester
public: void Init()
{
// Throughput publisher
this->throughputPub = this->node.Advertise<ignition::msgs::Bytes>(
this->throughputPub = this->node.Advertise<gz::msgs::Bytes>(
"/benchmark/throughput/request");
if (!this->throughputPub)
{
Expand All @@ -314,7 +314,7 @@ class PubTester
}

// Latency publisher
this->latencyPub = this->node.Advertise<ignition::msgs::Bytes>(
this->latencyPub = this->node.Advertise<gz::msgs::Bytes>(
"/benchmark/latency/request");
if (!this->latencyPub)
{
Expand Down Expand Up @@ -534,7 +534,7 @@ class PubTester

/// \brief Callback that handles throughput replies
/// \param[in] _msg The reply message
private: void ThroughputCb(const ignition::msgs::Bytes &_msg)
private: void ThroughputCb(const gz::msgs::Bytes &_msg)
{
// Lock
std::unique_lock<std::mutex> lk(this->mutex);
Expand Down Expand Up @@ -563,7 +563,7 @@ class PubTester

/// \brief Callback that handles latency replies
/// \param[in] _msg The reply message
private: void LatencyCb(const ignition::msgs::Bytes &_msg)
private: void LatencyCb(const gz::msgs::Bytes &_msg)
{
// End the time.
this->timeEnd = std::chrono::high_resolution_clock::now();
Expand Down Expand Up @@ -603,7 +603,7 @@ class PubTester
private: std::mutex mutex;

/// \brief Message that is sent.
private: ignition::msgs::Bytes msg;
private: gz::msgs::Bytes msg;

/// \brief Size of the message currently under test
private: uint64_t dataSize = 0;
Expand All @@ -618,13 +618,13 @@ class PubTester
private: uint64_t sentMsgs = 100;

/// \brief Communication node
private: ignition::transport::Node node;
private: gz::transport::Node node;

/// \brief Throughput publisher
private: ignition::transport::Node::Publisher throughputPub;
private: gz::transport::Node::Publisher throughputPub;

/// \brief Latency publisher
private: ignition::transport::Node::Publisher latencyPub;
private: gz::transport::Node::Publisher latencyPub;

/// \brief Used to stop the test.
private: bool stop = false;
Expand Down
10 changes: 5 additions & 5 deletions example/custom_query.cc
Original file line number Diff line number Diff line change
Expand Up @@ -28,17 +28,17 @@
//////////////////////////////////////////////////
/// \brief Query for all the topics in reverse
class AllTopicsReverse final
: public virtual ignition::transport::log::QueryOptions
: public virtual gz::transport::log::QueryOptions
{
// See documentation on QueryOptions
public: std::vector<ignition::transport::log::SqlStatement>
public: std::vector<gz::transport::log::SqlStatement>
GenerateStatements(
const ignition::transport::log::Descriptor &/*_descriptor*/)
const gz::transport::log::Descriptor &/*_descriptor*/)
const override
{
// The preamble has all the necessary joins and the correct column order
// for a SELECT statement that returns messages.
ignition::transport::log::SqlStatement statement =
gz::transport::log::SqlStatement statement =
this->StandardMessageQueryPreamble();
// Reverse the order of the messages
statement.statement += "ORDER BY messages.time_recv DESC;";
Expand All @@ -55,7 +55,7 @@ int main(int argc, char *argv[])
return -1;
}

ignition::transport::log::Log log;
gz::transport::log::Log log;
if (!log.Open(argv[1]))
{
std::cerr << "Failed to open log\n";
Expand Down
2 changes: 1 addition & 1 deletion example/playback.cc
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ int main(int argc, char *argv[])
return -1;
}

ignition::transport::log::Playback player(argv[1]);
gz::transport::log::Playback player(argv[1]);

// Playback all topics
const int64_t addTopicResult = player.AddTopic(std::regex(".*"));
Expand Down
6 changes: 3 additions & 3 deletions example/publisher.cc
Original file line number Diff line number Diff line change
Expand Up @@ -45,18 +45,18 @@ int main(int argc, char **argv)
std::signal(SIGTERM, signal_handler);

// Create a transport node and advertise a topic.
ignition::transport::Node node;
gz::transport::Node node;
std::string topic = "/foo";

auto pub = node.Advertise<ignition::msgs::StringMsg>(topic);
auto pub = node.Advertise<gz::msgs::StringMsg>(topic);
if (!pub)
{
std::cerr << "Error advertising topic [" << topic << "]" << std::endl;
return -1;
}

// Prepare the message.
ignition::msgs::StringMsg msg;
gz::msgs::StringMsg msg;
msg.set_data("HELLO");

// Publish messages at 1Hz.
Expand Down
4 changes: 2 additions & 2 deletions example/publisher_c.cc
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ int main(int argc, char **argv)
const char *topic = "/foo";

// Prepare the message.
ignition::msgs::StringMsg msg;
gz::msgs::StringMsg msg;
msg.set_data("HELLO");

// Get the size of the serialized message
Expand All @@ -62,7 +62,7 @@ int main(int argc, char **argv)
msg.SerializeToArray(buffer, size);

// Prepare the message.
ignition::msgs::StringMsg msgRed;
gz::msgs::StringMsg msgRed;
msgRed.set_data("RED HELLO");

// Get the size of the serialized message
Expand Down
4 changes: 2 additions & 2 deletions example/publisher_c_fast.cc
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ int main(int argc, char **argv)
const char *topic = "/foo";

// Prepare the message.
ignition::msgs::StringMsg msg;
gz::msgs::StringMsg msg;
msg.set_data("HELLO");

// Get the size of the serialized message
Expand All @@ -58,7 +58,7 @@ int main(int argc, char **argv)
msg.SerializeToArray(buffer, size);

// Prepare the message.
ignition::msgs::StringMsg msgRed;
gz::msgs::StringMsg msgRed;
msgRed.set_data("RED HELLO");

// Get the size of the serialized message
Expand Down
2 changes: 1 addition & 1 deletion example/publisher_custom_msg.cc
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ int main(int argc, char **argv)
std::signal(SIGTERM, signal_handler);

// Create a transport node and advertise a topic.
ignition::transport::Node node;
gz::transport::Node node;
std::string topic = "/foo";

auto pub = node.Advertise<example::msgs::StringMsg>(topic);
Expand Down
4 changes: 2 additions & 2 deletions example/publisher_raw.cc
Original file line number Diff line number Diff line change
Expand Up @@ -45,10 +45,10 @@ int main(int argc, char **argv)
std::signal(SIGTERM, signal_handler);

// Create a transport node and advertise a topic.
ignition::transport::Node node;
gz::transport::Node node;
std::string topic = "/foo";

ignition::msgs::StringMsg msg;
gz::msgs::StringMsg msg;
msg.set_data("HELLO");

auto pub = node.Advertise(topic, msg.GetTypeName());
Expand Down
6 changes: 3 additions & 3 deletions example/record.cc
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ int main(int argc, char *argv[])
return -1;
}

ignition::transport::log::Recorder recorder;
gz::transport::log::Recorder recorder;

// Record all topics
const int64_t addTopicResult = recorder.AddTopic(std::regex(".*"));
Expand All @@ -49,7 +49,7 @@ int main(int argc, char *argv[])

// Begin recording, saving received messages to the given file
const auto result = recorder.Start(argv[1]);
if (ignition::transport::log::RecorderError::SUCCESS != result)
if (gz::transport::log::RecorderError::SUCCESS != result)
{
std::cerr << "Failed to start recording: " << static_cast<int64_t>(result)
<< "\n";
Expand All @@ -60,7 +60,7 @@ int main(int argc, char *argv[])
<< std::endl;

// Wait until the interrupt signal is sent.
ignition::transport::waitForShutdown();
gz::transport::waitForShutdown();

recorder.Stop();

Expand Down
6 changes: 3 additions & 3 deletions example/requester.cc
Original file line number Diff line number Diff line change
Expand Up @@ -23,13 +23,13 @@
int main(int argc, char **argv)
{
// Create a transport node.
ignition::transport::Node node;
gz::transport::Node node;

// Prepare the input parameters.
ignition::msgs::StringMsg req;
gz::msgs::StringMsg req;
req.set_data("HELLO");

ignition::msgs::StringMsg rep;
gz::msgs::StringMsg rep;
bool result;
unsigned int timeout = 5000;

Expand Down
Loading

0 comments on commit 82bdd73

Please sign in to comment.