Skip to content

Commit

Permalink
Merge pull request #2008 from ros/backports_melodic
Browse files Browse the repository at this point in the history
changes between 1.15.8 (Noetic) and 1.14.6 for backporting into Melodic
  • Loading branch information
dirk-thomas authored Jul 24, 2020
2 parents ce22005 + 6a23fd7 commit f11086c
Show file tree
Hide file tree
Showing 6 changed files with 42 additions and 21 deletions.
1 change: 0 additions & 1 deletion clients/rospy/src/rospy/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -113,7 +113,6 @@
'logerr_once', 'logfatal_once',
'parse_rosrpc_uri',
'MasterProxy',
'NodeProxy',
'ROSException',
'ROSSerializationException',
'ROSInitException',
Expand Down
2 changes: 1 addition & 1 deletion tools/rosmaster/src/rosmaster/registrations.py
Original file line number Diff line number Diff line change
Expand Up @@ -125,7 +125,7 @@ def shutdown_node_task(api, caller_id, reason):
@type reason: str
"""
try:
xmlrpcapi(api).shutdown('/master', reason)
xmlrpcapi(api).shutdown('/master', "[{}] Reason: {}".format(caller_id, reason))
except:
pass #expected in many common cases
remove_server_proxy(api)
Expand Down
30 changes: 19 additions & 11 deletions tools/topic_tools/src/throttle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,8 @@ bool g_use_messages;
ros::Time g_last_time;
bool g_use_wallclock;
bool g_lazy;
bool g_force_latch = false;
bool g_force_latch_value = true;
ros::TransportHints g_th;

class Sent
Expand Down Expand Up @@ -87,24 +89,29 @@ void conn_cb(const ros::SingleSubscriberPublisher&)
}
}

bool is_latching(const boost::shared_ptr<const ros::M_string>& connection_header)
{
if (connection_header)
{
ros::M_string::const_iterator it = connection_header->find("latching");
if ((it != connection_header->end()) && (it->second == "1"))
{
ROS_DEBUG("input topic is latched; latching output topic to match");
return true;
}
}

return false;
}

void in_cb(const ros::MessageEvent<ShapeShifter>& msg_event)
{
boost::shared_ptr<ShapeShifter const> const &msg = msg_event.getConstMessage();
boost::shared_ptr<const ros::M_string> const& connection_header = msg_event.getConnectionHeaderPtr();

if (!g_advertised)
{
// If the input topic is latched, make the output topic latched
bool latch = false;
if (connection_header)
{
ros::M_string::const_iterator it = connection_header->find("latching");
if((it != connection_header->end()) && (it->second == "1"))
{
ROS_DEBUG("input topic is latched; latching output topic to match");
latch = true;
}
}
const bool latch = g_force_latch ? g_force_latch_value : is_latching(connection_header);
g_pub = msg->advertise(*g_node, g_output_topic, 10, latch, conn_cb);
g_advertised = true;
printf("advertised as %s\n", g_output_topic.c_str());
Expand Down Expand Up @@ -192,6 +199,7 @@ int main(int argc, char **argv)
pnh.getParam("wall_clock", g_use_wallclock);
pnh.getParam("unreliable", unreliable);
pnh.getParam("lazy", g_lazy);
g_force_latch = pnh.getParam("force_latch", g_force_latch_value);

if (unreliable)
g_th.unreliable().reliable(); // Prefers unreliable, but will accept reliable.
Expand Down
8 changes: 8 additions & 0 deletions utilities/xmlrpcpp/include/xmlrpcpp/XmlRpcValue.h
Original file line number Diff line number Diff line change
Expand Up @@ -95,6 +95,13 @@ namespace XmlRpc {
operator BinaryData&() { assertTypeOrInvalid(TypeBase64); return *_value.asBinary; }
operator struct tm&() { assertTypeOrInvalid(TypeDateTime); return *_value.asTime; }

operator const bool&() const { assertTypeOrInvalid(TypeBoolean); return _value.asBool; }
operator const int&() const { assertTypeOrInvalid(TypeInt); return _value.asInt; }
operator const double&() const { assertTypeOrInvalid(TypeDouble); return _value.asDouble; }
operator const std::string&() const { assertTypeOrInvalid(TypeString); return *_value.asString; }
operator const BinaryData&() const { assertTypeOrInvalid(TypeBase64); return *_value.asBinary; }
operator const struct tm&() const { assertTypeOrInvalid(TypeDateTime); return *_value.asTime; }

XmlRpcValue const& operator[](int i) const { assertArray(i+1); return _value.asArray->at(i); }
XmlRpcValue& operator[](int i) { assertArray(i+1); return _value.asArray->at(i); }

Expand Down Expand Up @@ -147,6 +154,7 @@ namespace XmlRpc {
void invalidate();

// Type checking
void assertTypeOrInvalid(Type t) const;
void assertTypeOrInvalid(Type t);
void assertArray(int size) const;
void assertArray(int size);
Expand Down
6 changes: 6 additions & 0 deletions utilities/xmlrpcpp/src/XmlRpcValue.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,12 @@ namespace XmlRpc {


// Type checking
void XmlRpcValue::assertTypeOrInvalid(Type t) const
{
if (_type != t)
throw XmlRpcException("type error");
}

void XmlRpcValue::assertTypeOrInvalid(Type t)
{
if (_type == TypeInvalid)
Expand Down
16 changes: 8 additions & 8 deletions utilities/xmlrpcpp/test/TestValues.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ TEST(XmlRpc, Bool) {
}

TEST(XmlRpc, testBoolean) {
XmlRpcValue booleanFalse(false);
const XmlRpcValue booleanFalse(false);
XmlRpcValue booleanTrue(true);
int offset = 0;
XmlRpcValue booleanFalseXml("<value><boolean>0</boolean></value>", &offset);
Expand All @@ -75,7 +75,7 @@ TEST(XmlRpc, testBoolean) {

// Int
TEST(XmlRpc, testInt) {
XmlRpcValue int0(0);
const XmlRpcValue int0(0);
ASSERT_EQ(XmlRpcValue::TypeInt, int0.getType());

XmlRpcValue int1(1);
Expand Down Expand Up @@ -110,7 +110,7 @@ TEST(XmlRpc, testInt) {

TEST(XmlRpc, testDouble) {
// Double
XmlRpcValue d(43.7);
const XmlRpcValue d(43.7);
ASSERT_EQ(XmlRpcValue::TypeDouble, d.getType());
EXPECT_EQ("<value><double>43.700000000000003</double></value>", d.toXml());
EXPECT_DOUBLE_EQ(43.7, double(d));
Expand All @@ -130,7 +130,7 @@ TEST(XmlRpc, testDouble) {

TEST(XmlRpc, testString) {
// String
XmlRpcValue s("Now is the time <&");
const XmlRpcValue s("Now is the time <&");
ASSERT_EQ(XmlRpcValue::TypeString, s.getType());
EXPECT_EQ(18, s.size());
EXPECT_EQ("<value>Now is the time &lt;&amp;</value>", s.toXml());
Expand Down Expand Up @@ -178,7 +178,7 @@ TEST(XmlRpc, testDateTime) {
// DateTime
int offset = 0;
// Construct from XML
XmlRpcValue dateTime(
const XmlRpcValue dateTime(
"<value><dateTime.iso8601>19040503T03:12:35</dateTime.iso8601></value>",
&offset);
ASSERT_EQ(XmlRpcValue::TypeDateTime, dateTime.getType());
Expand Down Expand Up @@ -286,7 +286,7 @@ TEST(XmlRpc, testArray) {
EXPECT_EQ(a, aXml);

// Array copy works
XmlRpcValue copy(a);
const XmlRpcValue copy(a);
ASSERT_EQ(a.getType(), copy.getType());
ASSERT_EQ(a.size(), copy.size());
for (int i = 0; i < 3; i++) {
Expand Down Expand Up @@ -345,7 +345,7 @@ TEST(XmlRpc, testStruct) {
"</struct></value>";

int offset = 0;
XmlRpcValue structXml(csStructXml, &offset);
const XmlRpcValue structXml(csStructXml, &offset);
EXPECT_EQ(struct1, structXml);

for (XmlRpcValue::iterator itr = struct1.begin(); itr != struct1.end();
Expand Down Expand Up @@ -399,7 +399,7 @@ TEST(XmlRpc, testStruct) {

TEST(XmlRpc, base64) {
char data[] = {1, 2};
XmlRpcValue bin(data, 2);
const XmlRpcValue bin(data, 2);

EXPECT_EQ(XmlRpcValue::TypeBase64, bin.getType());
EXPECT_EQ(2, bin.size());
Expand Down

0 comments on commit f11086c

Please sign in to comment.