Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

micro-ROS Library auto-update 17-04-2022 06:08 #483

Merged
merged 1 commit into from
Apr 18, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions built_packages
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ https://github.com/ros2/ament_cmake_ros.git 60572fa1bec50b9e6fbe64e1b23640d21c15
https://github.com/ros-controls/control_msgs a555c37f1a3536bb452ea555c58fdd9344d87614
https://github.com/ros2/common_interfaces.git f3cb4848560e91596e7688e8ac1816828fa460cb
https://github.com/ros2/rosidl_defaults.git 1f1ee2a6169837b10302ffb2a52fb2f2a57239b2
https://github.com/ros2/rcl.git 24ad44e984ad36be2be818d558bc0710329a5da7
https://github.com/ros2/rcl.git 71baed437d9b50c303f46ffe79ca118ad14e1735
https://github.com/ros2/unique_identifier_msgs.git 27767cefcf8a80da44641dc208c57722c28aa11c
https://github.com/ros2/rosidl.git de0556a13be36ca62d6a6573da369e3fe2eb204c
https://github.com/ros2/test_interface_files.git a0c8f5e338490ddf8b98238dce35c06810115e8b
Expand All @@ -25,7 +25,7 @@ https://github.com/eProsima/Micro-XRCE-DDS-Client.git 9b9278c0b3a633aa7ad634bda2
https://github.com/eProsima/Micro-CDR.git cb4403a8780095df94a7b1936b1e00153c90070d
https://github.com/yaml/libyaml.git 2c891fc7a770e8ba2fec34fc6b545c672beb37e6
https://github.com/micro-ROS/rcl 067ef1effe7ada177ffa1fc3b58237eaceb0699c
https://github.com/ros2/rclc 79a2df204ff8f745539d842cf669fadd1dd4ca7e
https://github.com/ros2/rclc b73a773ca725e67898ece0531849d20077967456
https://github.com/micro-ROS/rosidl_typesupport_microxrcedds.git 28b88ac044e504095fbe9381508925e0aec7bc24
https://github.com/micro-ROS/rcutils 342c39ce7cbc3d90ea1d4552ddcbb45ae14bec6d
https://github.com/micro-ROS/rosidl_typesupport.git 0a28c7b07241b2f287c5f6f8090eb6a92cb4519f
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ enum
/// Constant 'PREEMPTED'.
/**
* The goal received a cancel request after it started executing
* and has since completed its execution (Terminal State).
* and has since completed its execution (Terminal State).
*/
enum
{
Expand Down Expand Up @@ -78,7 +78,7 @@ enum
/// Constant 'PREEMPTING'.
/**
* The goal received a cancel request after it started executing
* and has not yet completed execution.
* and has not yet completed execution.
*/
enum
{
Expand All @@ -88,7 +88,7 @@ enum
/// Constant 'RECALLING'.
/**
* The goal received a cancel request before it started executing, but
* the action server has not yet confirmed that the goal is canceled.
* the action server has not yet confirmed that the goal is canceled.
*/
enum
{
Expand All @@ -108,7 +108,7 @@ enum
/// Constant 'LOST'.
/**
* An action client can determine that a goal is LOST. This should not
* be sent over the wire by an action server.
* be sent over the wire by an action server.
*/
enum
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -122,9 +122,9 @@ typedef struct control_msgs__action__FollowJointTrajectory_Result
/// Human readable description of the error code. Contains complementary
/// information that is especially useful when execution fails, for instance:
/// - INVALID_GOAL: The reason for the invalid goal (e.g., the requested
/// trajectory is in the past).
/// trajectory is in the past).
/// - INVALID_JOINTS: The mismatch between the expected controller joints
/// and those provided in the goal.
/// and those provided in the goal.
/// - PATH_TOLERANCE_VIOLATED and GOAL_TOLERANCE_VIOLATED: Which joint
/// violated which tolerance, and by how much.
rosidl_runtime_c__String error_string;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,8 +30,8 @@ extern "C"
* abort.
*
* There are two special values for tolerances:
* * 0 - The tolerance is unspecified and will remain at whatever the default is
* * -1 - The tolerance is "erased". If there was a default, the joint will be
* * 0 - The tolerance is unspecified and will remain at whatever the default is
* * -1 - The tolerance is "erased". If there was a default, the joint will be
* allowed to move without restriction.
*/
typedef struct control_msgs__msg__JointTolerance
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,9 +31,9 @@ typedef struct geometry_msgs__msg__Inertia
/// Center of mass
geometry_msgs__msg__Vector3 com;
/// Inertia Tensor
/// | ixx ixy ixz |
/// | ixx ixy ixz |
/// I = | ixy iyy iyz |
/// | ixz iyz izz |
/// | ixz iyz izz |
double ixx;
double ixy;
double ixz;
Expand Down
214 changes: 206 additions & 8 deletions libmicroros/include/rclc_parameter/rclc_parameter.h
Original file line number Diff line number Diff line change
Expand Up @@ -62,13 +62,43 @@ typedef struct rcl_interfaces__srv__ListParameters_Response ListParameters_Respo
typedef struct rcl_interfaces__msg__Parameter Parameter;
typedef struct rcl_interfaces__msg__ParameterValue ParameterValue;
typedef struct rcl_interfaces__msg__Parameter__Sequence Parameter__Sequence;
typedef struct rcl_interfaces__msg__ParameterDescriptor ParameterDescriptor;
typedef struct rcl_interfaces__msg__ParameterDescriptor__Sequence ParameterDescriptor__Sequence;
typedef struct rcl_interfaces__msg__ParameterEvent ParameterEvent;

// Number of RCLC executor handles required for a parameter server
#define RCLC_PARAMETER_EXECUTOR_HANDLES_NUMBER 5
#define RCLC_EXECUTOR_PARAMETER_SERVER_HANDLES 5
#define RCLC_PARAMETER_MODIFICATION_REJECTED 4001
#define RCLC_PARAMETER_TYPE_MISMATCH 4002
#define RCLC_PARAMETER_UNSUPORTED_ON_LOW_MEM 4003
#define RCLC_PARAMETER_DISABLED_ON_CALLBACK 40004

// On parameter modified callback
typedef void (* ModifiedParameter_Callback)(Parameter * param);
/**
* Parameter event callback.
* This callback will allow the user to allow or reject the following events:
* - Parameter value change: Internal and external parameter set on existing parameters.
* - Parameter creation: External parameter set on unexisting parameter if `allow_undeclared_parameters` is set.
* - Parameter delete: External parameter delete on existing parameter.
*
* Parameters modifications are disabled while this callback is executed.
*
* <hr>
* Attribute | Adherence
* ------------------ | -------------
* Allocates Memory | No
* Thread-Safe | No
* Uses Atomics | No
* Lock-Free | No
*
* \param[in] old_param Parameter actual value, `NULL` for new parameter request.
* \param[in] new_param Parameter new value, `NULL` for parameter removal request.
* \param[in] context Context of the callback.
* \return `true` to accept the parameter event. If the operation was rejected, `false` is returned.
*/
typedef bool (* rclc_parameter_callback_t)(
const Parameter * old_param,
const Parameter * new_param,
void * context);

// Allowed RCLC parameter types
typedef enum rclc_parameter_type_t
Expand All @@ -84,6 +114,8 @@ typedef struct rclc_parameter_options_t
{
bool notify_changed_over_dds;
size_t max_params;
bool allow_undeclared_parameters;
bool low_mem_mode;
} rclc_parameter_options_t;

// Container for RCLC parameter server
Expand Down Expand Up @@ -112,12 +144,17 @@ typedef struct rclc_parameter_server_t
DescribeParameters_Response describe_response;

Parameter__Sequence parameter_list;
ParameterDescriptor__Sequence parameter_descriptors;

ParameterEvent event_list;

ModifiedParameter_Callback on_modification;
rclc_parameter_callback_t on_modification;
void * context;
bool on_callback;

bool notify_changed_over_dds;
bool allow_undeclared_parameters;
bool low_mem_mode;
} rclc_parameter_server_t;

/**
Expand Down Expand Up @@ -202,10 +239,35 @@ RCLC_PARAMETER_PUBLIC
rcl_ret_t rclc_executor_add_parameter_server(
rclc_executor_t * executor,
rclc_parameter_server_t * parameter_server,
ModifiedParameter_Callback on_modification);
rclc_parameter_callback_t on_modification);

/**
* Adds a RCLC parameter server to an RCLC executor
*
* <hr>
* Attribute | Adherence
* ------------------ | -------------
* Allocates Memory | Yes
* Thread-Safe | No
* Uses Atomics | No
* Lock-Free | No
*
* \param[in] executor RCLC executor
* \param[in] parameter_server preallocated rclc_parameter_server_t
* \param[in] on_modification on parameter modification callback
* \param[in] context context of the parameter modification callback
* \return `RCL_RET_OK` if success
*/
RCLC_PARAMETER_PUBLIC
rcl_ret_t rclc_executor_add_parameter_server_with_context(
rclc_executor_t * executor,
rclc_parameter_server_t * parameter_server,
rclc_parameter_callback_t on_modification,
void * context);

/**
* Adds a RCLC parameter to a server
* This method is disabled on user callback execution.
*
* <hr>
* Attribute | Adherence
Expand All @@ -228,7 +290,30 @@ rclc_add_parameter(
rclc_parameter_type_t type);

/**
* Sets the value of an existing a RCLC bool parameter
* Deletes a RCLC parameter from the server.
* This method is disabled on user callback execution.
*
* <hr>
* Attribute | Adherence
* ------------------ | -------------
* Allocates Memory | No
* Thread-Safe | No
* Uses Atomics | No
* Lock-Free | No
*
* \param[in] parameter_server preallocated rclc_parameter_server_t
* \param[in] parameter_name name of the parameter
* \return `RCL_RET_OK` if success
*/
RCLC_PARAMETER_PUBLIC
rcl_ret_t
rclc_delete_parameter(
rclc_parameter_server_t * parameter_server,
const char * parameter_name);

/**
* Sets the value of an existing a RCLC bool parameter.
* This method is disabled on user callback execution.
*
* <hr>
* Attribute | Adherence
Expand All @@ -251,7 +336,8 @@ rclc_parameter_set_bool(
bool value);

/**
* Sets the value of an existing a RCLC integer parameter
* Sets the value of an existing a RCLC integer parameter.
* This method is disabled on user callback execution.
*
* <hr>
* Attribute | Adherence
Expand All @@ -274,7 +360,8 @@ rclc_parameter_set_int(
int64_t value);

/**
* Sets the value of an existing a RCLC double parameter
* Sets the value of an existing a RCLC double parameter.
* This method is disabled on user callback execution.
*
* <hr>
* Attribute | Adherence
Expand Down Expand Up @@ -365,6 +452,117 @@ rclc_parameter_get_double(
const char * parameter_name,
double * output);


/**
* Add a description to a parameter. (This feature is disabled in low memory mode.)
* This description will be returned on describe parameters requests.
*
* <hr>
* Attribute | Adherence
* ------------------ | -------------
* Allocates Memory | No
* Thread-Safe | No
* Uses Atomics | No
* Lock-Free | No
*
* \param[in] parameter_server preallocated rclc_parameter_server_t
* \param[in] parameter_name name of the parameter
* \param[in] parameter_description description of the parameter
* \param[in] additional_constraints constraints description
* \param[in] read_only read only flag
* \return `RCL_RET_OK` if success
*/
RCLC_PARAMETER_PUBLIC
rcl_ret_t
rclc_add_parameter_description(
rclc_parameter_server_t * parameter_server,
const char * parameter_name,
const char * parameter_description,
const char * additional_constraints);

/**
* Sets a parameter read only flag.
* Read only parameters can only be modified from the `rclc_parameter_set` API.
* This method is disabled on user callback execution.
*
* <hr>
* Attribute | Adherence
* ------------------ | -------------
* Allocates Memory | No
* Thread-Safe | No
* Uses Atomics | No
* Lock-Free | No
*
* \param[in] parameter_server preallocated rclc_parameter_server_t
* \param[in] parameter_name name of the parameter
* \param[in] read_only read only flag
* \return `RCL_RET_OK` if success
*/
RCLC_PARAMETER_PUBLIC
rcl_ret_t
rclc_set_parameter_read_only(
rclc_parameter_server_t * parameter_server,
const char * parameter_name,
bool read_only);

/**
* Sets a constraint on an integer parameter.
* This constraint specification will be returned on describe parameters requests.
* This method is disabled on user callback execution.
*
* <hr>
* Attribute | Adherence
* ------------------ | -------------
* Allocates Memory | No
* Thread-Safe | No
* Uses Atomics | No
* Lock-Free | No
*
* \param[in] parameter_server preallocated rclc_parameter_server_t
* \param[in] parameter_name name of the parameter
* \param[in] from_value start value for valid values, inclusive.
* \param[in] to_value end value for valid values, inclusive.
* \param[in] step size of valid steps between the from and to bound.
* \return `RCL_RET_OK` if success
*/
RCLC_PARAMETER_PUBLIC
rcl_ret_t
rclc_add_parameter_constraint_integer(
rclc_parameter_server_t * parameter_server,
const char * parameter_name,
int64_t from_value,
int64_t to_value,
uint64_t step);

/**
* Sets a constraint on an double parameter.
* This constraint specification will be returned on describe parameters requests.
* This method is disabled on user callback execution.
*
* <hr>
* Attribute | Adherence
* ------------------ | -------------
* Allocates Memory | No
* Thread-Safe | No
* Uses Atomics | No
* Lock-Free | No
*
* \param[in] parameter_server preallocated rclc_parameter_server_t
* \param[in] parameter_name name of the parameter
* \param[in] from_value start value for valid values, inclusive.
* \param[in] to_value end value for valid values, inclusive.
* \param[in] step size of valid steps between the from and to bound.
* \return `RCL_RET_OK` if success
*/
RCLC_PARAMETER_PUBLIC
rcl_ret_t
rclc_add_parameter_constraint_double(
rclc_parameter_server_t * parameter_server,
const char * parameter_name,
double from_value,
double to_value,
double step);

#if __cplusplus
}
#endif // if __cplusplus
Expand Down
Loading