This page describes major changes to roscpp applicable to the 1.2 release.

<<TableOfContents(3)>>

== Major Changes ==
=== Message/Service Changes ===
'''New Serialization API'''

Serialization has turned from polymorphic to template-based.  This removes the need for a `Message` base-class, and allows you to adapt existing C++ structures to ROS messages.  See [[http://www.ros.org/wiki/roscpp/Overview/MessagesSerializationAndAdaptingTypes]] for information on adapting types to ROS msg types.

An example use of this is to adapt builtin types to the `std_msgs` types.  For example, the following is now possible:
{{{
#!cplusplus
#include <std_msgs/builtin_uint32.h>
void callback(uint32_t val)
{
}

ros::Subscriber sub = nh.subscribe("my_topic", 0, callback);
ros::Publisher pub = nh.advertise<uint32_t>("my_topic", 0);
pub.publish(5);
}}}

Use of the `Message` base-class and members (`__getMD5Sum()`, `__connection_header`, etc.) are now deprecated.  md5sum/etc. retrieval is now done through traits: http://www.ros.org/wiki/roscpp/Overview/MessagesTraits.  The connection header is now accessible through a new type of callback argument, `MessageEvent` in a subscription callback:
{{{
#!cplusplus
void callback(const ros::MessageEvent<Msg const>& evt)
{
  ros::M_string& header = evt.getConnectionHeader();
}
}}}

Or `ServiceEvent` in a service callback:

{{{
#!cplusplus
void callback(const ros::ServiceEvent<Request, Response>& evt)
{
  ros::M_string& header = evt.getConnectionHeader();
}
}}}

For the rationale behind these changes as well as some implementation details, please see [[http://www.ros.org/wiki/roscpp/NewMessageAPIProposal]] and [[http://www.ros.org/wiki/roscpp/NewMessageAPIProposal2]]

This change is backwards compatible.  Old-style custom C++ messages will continue to work without changes until ROS 2.0, and messages will continue deriving from the `Message` base class until then as well.

'''Custom Allocator Support'''

Messages can now use an STL allocator of your choosing to do their container memory allocation.

{{{
#!cplusplus
ROS_DECLARE_MESSAGE_WITH_ALLOCATOR(visualization_msgs::Marker, MyMarker, MyAllocator);
MyMarker marker;
MyAllocator a;
MyMarker marker2(a);
...
}}}

See [[http://www.ros.org/wiki/roscpp/Overview/MessagesCustomAllocators]]

=== Publish/Subscribe Changes ===

'''Subscription Callback Types, Non-Const Subscriptions'''

In addition to `MessageEvent` shown above, it's now possible to use a number of different signatures for your callback:
{{{
#!cplusplus
void callback(const boost::shared_ptr<Msg const>&);
void callback(boost::shared_ptr<Msg const>);
void callback(const Msg&);
void callback(Msg);
}}}

You can also now request a non-const message, in which case a copy will be made if necessary (i.e. there are multiple subscriptions to the same topic in the same node).
{{{
#!cplusplus
void callback(const boost::shared_ptr<Msg>&);
}}}

These callback types are now supported in `message_filters` as well.

See [[http://www.ros.org/wiki/roscpp/Overview/Publishers%20and%20Subscribers#Callback_Signature]]

'''Fast Intraprocess Message Passing'''

It's now possible to send messages within a node without incurring a serialize/deserialize cost:

{{{
#!cplusplus
MsgPtr g_msg;
void callback(const MsgConstPtr& msg)
{
  ROS_ASSERT(msg == g_msg); // Should not fire
}

ros::Subscriber sub = nh.subscribe("my_topic", 0, callback);
ros::Publisher pub = nh.advertise<Msg>("my_topic", 0);
MsgPtr msg(new Msg);  // Note that this is a boost::shared_ptr
g_msg = msg;
pub.publish(msg);

// The following would *not* be no-copy
// Msg msg;
// pub.publish(msg);
}}}

'''Generated msg/srv Header Location Change'''

Generated .msg/.srv headers now go into `<package>/msg_gen` and `<package>/srv_gen` respectively.  Their include paths are automatically exported, and [[roswtf]] will now warn if you have `-I${prefix}/msg/cpp` in your manifest exports.

=== Subscription TCP Connection Retry ===
If a TCP connection to a publisher fails for any reason, roscpp will now attempt to retry that connection until it is notified by the master that the node has gone away.

The retry starts at 100ms after the connection is dropped, and backs off by doubling that time after every failure until it hits 20s.

=== Time Gotchas ===
roscpp no longer allows use of `ros::Time::now()` until the node has been started, either through the creation of the first `NodeHandle` or through `ros::start()`.  This is because we cannot know if we're using simulation time until we check the `/use_sim_time` parameter, and thus whatever time we return may be invalid.

If and only if you know you're not in a Node (like in a unit test), you can call `ros::Time::init()`.  You can also use `ros::WallTime` in this case.

== Additional Changes ==
 * Messages
  * Message generators have been rewritten in Python
  * Constants (including string constants) are now properly supported, and should never generate compiler or linker errors
  * serialization is now bounds checked and should not crash if invalid serialized data is received
  * Messages can now be printed to a `std::ostream` using `operator<<`
 * `CallbackQueue::callAvailable()` and `callOne()` methods are now recursive-safe, so you can call either of them from within a callback being invoked from the same `CallbackQueue`
 * Subscribing with `*` as the md5sum/datatype now decays to a real type (which then never changes) as soon as it receives the md5sum in any way (e.g. a publisher connects or a 2nd subscriber in the same node)
 * Added parameter validation to a number of methods.  They will throw a `ros::InvalidParameterException` if invalid
 * `advertise()` no longer accepts the `*` datatype/md5sum

== Major Bugs Fixed ==
 * Fixed possible starvation of subscription callbacks
 * Long-running timer callbacks no longer starve callbacks running from the same callback queue in different threads
 * No longer allows (silently with bugs) subscribing to the same topic with multiple different data types.  Will throw a `ros::ConflictingSubscriptionException` in this case
 * `UDPROS` now verifies topic md5sums
 * Fixed a number of bugs with `UDPROS`
 * Fixed a race condition that caused some connections to immediately close. Generally exposed itself as failed service calls if they were happening in quick succession.

== Deprecations ==
 * `set_X_size()`/`get_X_size()` message accessors
 * `Message::__getMD5Sum()`
 * `Message::__getDataType()`
 * `Message::__getMessageDefinition()`
 * `Message::__s_getMD5Sum()`
 * `Message::__s_getDataType()`
 * `Message::__s_getMessageDefinition()`
 * `Message::__connection_header`
 * `Message::serializationLength()`
 * `Message::serialize()`
 * `Message::deserialize()`
 * `Message::__serialized_length`