Class Transaction

Class Documentation

class Transaction

A transaction is a group of variable and constraint additions and subtractions that should all be processed at the same time.

This arises most often with graph edits, when you want to remove an existing constraint and replace it with one or more new constraints. You don’t want the removal to happen independently of the additions. All graph operations are contained within a Transaction object so that all operations are treated equally.

Public Types

using const_constraint_range = boost::any_range<const Constraint, boost::forward_traversal_tag>

A range of Constraint::SharedPtr objects.

An object representing a range defined by two iterators. It has begin() and end() methods (which means it can be used in range-based for loops), an empty() method, and a front() method for directly accessing the first member. When dereferenced, an iterator returns a const Constraint&.

using const_stamp_range = boost::any_range<const rclcpp::Time, boost::forward_traversal_tag>

A range of rclcpp::Time objects.

An object representing a range defined by two iterators. It has begin() and end() methods (which means it can be used in range-based for loops), an empty() method, and a front() method for directly accessing the first member. When dereferenced, an iterator returns a const rclcpp::Time&.

using const_uuid_range = boost::any_range<const UUID, boost::forward_traversal_tag>

A range of UUID objects.

An object representing a range defined by two iterators. It has begin() and end() methods (which means it can be used in range-based for loops), an empty() method, and a front() method for directly accessing the first member. When dereferenced, an iterator returns a const UUID&.

using const_variable_range = boost::any_range<const Variable, boost::forward_traversal_tag>

A range of Variable::SharedPtr objects.

An object representing a range defined by two iterators. It has begin() and end() methods (which means it can be used in range-based for loops), an empty() method, and a front() method for directly accessing the first member. When dereferenced, an iterator returns a const Variable&.

Public Functions

inline const rclcpp::Time &stamp() const

Read-only access to this transaction’s timestamp.

inline void stamp(const rclcpp::Time &stamp)

Write access to this transaction’s timestamp.

inline const_stamp_range involvedStamps() const

Read-only access to the set of timestamps involved in this transaction.

Returns:

An iterator range containing all involved timestamps, ordered oldest to newest

const rclcpp::Time &minStamp() const

Read-only access to the minimum (oldest), timestamp among the transaction’s stamp and all involved timestamps, if any.

Returns:

The minimum (oldest) timestamp.

const rclcpp::Time &maxStamp() const

Read-only access to the maximum (newest) timestamp among the transaction’s stamp and all involved timestamps, if any.

Returns:

The maximum (newest) timestamp.

const_constraint_range addedConstraints() const

Read-only access to the added constraints.

Returns:

An iterator range containing all added constraints

inline const_uuid_range removedConstraints() const

Read-only access to the removed constraints.

Returns:

An iterator range containing all removed constraint UUIDs

const_variable_range addedVariables() const

Read-only access to the added variables.

Returns:

An iterator range containing all added variables

inline const_uuid_range removedVariables() const

Read-only access to the removed variables.

Returns:

An iterator range containing all removed variable UUIDs

bool empty() const

Check if the transaction is empty, i.e. it has no added or removed constraints or variables, and no involved stamps.

Returns:

True if the transaction is empty, false otherwise

void addInvolvedStamp(const rclcpp::Time &stamp)

Add a timestamp to the “involved stamps” collection.

Duplicate timestamps will be ignored, so adding a stamp multiple times will have no effect.

Parameters:

stamp[in] The timestamp to be added

void addConstraint(Constraint::SharedPtr constraint, bool overwrite = false)

Add a constraint to this transaction.

The transaction will shared ownership of the provided constraint. This function also performs several checks to ensure the same constraint is not added twice, or added and removed.

Parameters:
  • constraint[in] The constraint to be added

  • overwrite[in] Flag indicating the provided constraint should overwrite an existing constraint with the same UUID

void removeConstraint(const UUID &constraint_uuid)

Remove a constraint from this transaction if it was previously added, or mark the constraint for removal from the graph.

The constraint UUID is marked to be removed by the receiver of this Transaction. This function also performs several checks to ensure the same constraint is not removed twice, or added and removed.

Parameters:

constraint_uuid[in] The UUID of the constraint to remove

void addVariable(Variable::SharedPtr variable, bool overwrite = false)

Add a variable to this transaction.

The transaction will shared ownership of the provided variable. This function also performs several checks to ensure the same variable is not added twice, or added and removed.

Parameters:
  • variable[in] The variable to be added

  • overwrite[in] Flag indicating the provided variable should overwrite an existing variable with the same UUID

void removeVariable(const UUID &variable_uuid)

Remove the variable from this transaction if it was previously added, or mark the variable for removal from the graph.

The variable UUID is marked to be removed by the receiver of this Transaction. This function also performs several checks to ensure the same variable is not removed twice, or added and removed.

Parameters:

variable_uuid[in] The UUID of the variable to remove

void merge(const Transaction &other, bool overwrite = false)

Merge the contents of another transaction into this one.

Parameters:
  • other[in] The transaction to merge in

  • overwrite[in] Flag indicating that variables and constraints in other should overwrite existing variables and constraints with the UUIDs.

void print(std::ostream &stream = std::cout) const

Print a human-readable description of the transaction to the provided stream.

Parameters:

stream[out] The stream to write to. Defaults to stdout.

Transaction::UniquePtr clone() const

Perform a deep copy of the Transaction and return a unique pointer to the copy.

Unique pointers can be implicitly upgraded to shared pointers if needed.

Returns:

A unique pointer to a new instance of the most-derived Variable

void serialize(fuse_core::BinaryOutputArchive&) const

Serialize this Constraint into the provided binary archive.

Parameters:

archive[out] - The archive to serialize this constraint into

void serialize(fuse_core::TextOutputArchive&) const

Serialize this Constraint into the provided text archive.

Parameters:

archive[out] - The archive to serialize this constraint into

void deserialize(fuse_core::BinaryInputArchive&)

Deserialize data from the provided binary archive into this Constraint.

Parameters:

archive[in] - The archive holding serialized Constraint data

void deserialize(fuse_core::TextInputArchive&)

Deserialize data from the provided text archive into this Constraint.

Parameters:

archive[in] - The archive holding serialized Constraint data

Friends

friend class boost::serialization::access