def test_map_hypothesis_vector3_to_rospy(): hypothesis_vector3 = vector3().example() rospy_type = map_vector3(hypothesis_vector3) assert isinstance( rospy_type, Vector3 ), 'Hypothesis type ({}) could not be mapped to rospy type ({}).'.format( hypothesis_type, rospy_type)
def imu(draw, header=header(), orientation=quaternion(), orientation_covariance=array(elements=float64(), min_size=9, max_size=9), angular_velocity=vector3(), angular_velocity_covariance=array(elements=float64(), min_size=9, max_size=9), linear_acceleration=vector3(), linear_acceleration_covariance=array(elements=float64(), min_size=9, max_size=9)): """ Generate values for ROS1 sensor_msgs/Imu.msg. Parameters ---------- header : hypothesis_ros.std_msgs.header() Strategy to generate header value. (Default: Default hypothesis_ros strategy.) orientation : hypothesis_ros.geometry_msgs.Quaternion() Strategy to generate orientation value. (Default: Default hypothesis_ros strategy.) orientation_covariance : hypothesis_ros.message_fields.array() Strategy to generate orientation_covariance value. (Default: Customized to 9 elements of type float64().) angular_velocity : hypothesis_ros.messages.geometry_msgs.vector3() Strategy to generate angular_velocity value. (Default: Default hypothesis_ros strategy.) angular_velocity_covariance : hypothesis_ros.message_fields.array() Strategy to generate angular_velocity_covariance value. (Default: Customized to 9 elements of type float64().) linear_acceleration : hypothesis_ros.messages.geometry_msgs.vector3() Strategy to generate linear_acceleration value. (Default: Default hypothesis_ros strategy.) linear_acceleration_covariance : hypothesis_ros.messages.message_fields.array() Strategy to generate linear_acceleration_covariance value. (Default: Customized to 9 elements of type float64().) """ header_value = draw(header) orientation_value = draw(orientation) orientation_covariance_value = draw(orientation_covariance) angular_velocity_value = draw(angular_velocity) angular_velocity_covariance_value = draw(angular_velocity_covariance) linear_acceleration_value = draw(linear_acceleration) linear_acceleration_covariance_value = draw(linear_acceleration_covariance) # TODO: add validation return _Imu(header_value, orientation_value, orientation_covariance_value, angular_velocity_value, angular_velocity_covariance_value, linear_acceleration_value, linear_acceleration_covariance_value)
array, float64, uint32, time, ) @given( array(elements=transform_stamped( header(seq=uint32(min_value=0, max_value=0), stamp=time(secs=uint32(min_value=1, max_value=1), nsecs=uint32(min_value=2, max_value=2)), frame_id=just('some_tf_frame_name')), just('some_child_frame_id'), transform(translation=vector3(x=float64(min_value=1.0, max_value=1.0), y=float64(min_value=2.0, max_value=2.0), z=float64(min_value=3.0, max_value=3.0)), rotation=quaternion(x=float64(min_value=1.0, max_value=1.0), y=float64(min_value=2.0, max_value=2.0), z=float64(min_value=3.0, max_value=3.0), w=float64(min_value=4.0, max_value=4.0)))), min_size=2, max_size=2)) def test_tfmessage_accepts_customized_strategies(generated_value): """Exemplary customized TFMessage.""" assert generated_value == [ ((0, (1, 2), 'some_tf_frame_name'), 'some_child_frame_id', ((1.0, 2.0, 3.0), (1.0, 2.0, 3.0, 4.0))), ((0, (1, 2), 'some_tf_frame_name'), 'some_child_frame_id', ((1.0, 2.0, 3.0), (1.0, 2.0, 3.0, 4.0)))
@given(imu(header(seq=uint32(min_value=0, max_value=0), stamp=time(secs=uint32(min_value=1, max_value=1), nsecs=uint32(min_value=2, max_value=2) ), frame_id=just('some_tf_frame_name') ), quaternion(x=float64(min_value=1.0, max_value=1.0), y=float64(min_value=2.0, max_value=2.0), z=float64(min_value=3.0, max_value=3.0), w=float64(min_value=4.0, max_value=4.0) ), array(elements=float64(min_value=1.0, max_value=1.0), min_size=9, max_size=9), vector3(x=float64(min_value=1.0, max_value=1.0), y=float64(min_value=2.0, max_value=2.0), z=float64(min_value=3.0, max_value=3.0) ), array(elements=float64(min_value=2.0, max_value=2.0), min_size=9, max_size=9), vector3(x=float64(min_value=1.0, max_value=1.0), y=float64(min_value=2.0, max_value=2.0), z=float64(min_value=3.0, max_value=3.0) ), array(elements=float64(min_value=3.0, max_value=3.0), min_size=9, max_size=9) ) ) def test_imu_accepts_customized_strategies(generated_values): """Exemplary customized imu message fields.""" assert generated_values == ((0, (1, 2), 'some_tf_frame_name'), (1.0, 2.0, 3.0, 4.0), [1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0], (1.0, 2.0, 3.0),