Skip to content

Commit

Permalink
New platform independent Serial interface (#21723)
Browse files Browse the repository at this point in the history
  • Loading branch information
katzfey authored Mar 22, 2024
1 parent bb9f4d4 commit 69028f3
Show file tree
Hide file tree
Showing 20 changed files with 1,902 additions and 177 deletions.
2 changes: 1 addition & 1 deletion boards/modalai/fc-v2/default.px4board
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
CONFIG_MODULES_SENSORS=y
CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y
# CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_UXRCE_DDS_CLIENT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
Expand Down
1 change: 1 addition & 0 deletions boards/modalai/voxl2-slpi/default.px4board
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@ CONFIG_DRIVERS_ACTUATORS_VOXL_ESC=y
CONFIG_DRIVERS_BAROMETER_INVENSENSE_ICP101XX=y
CONFIG_DRIVERS_DISTANCE_SENSOR_VL53L0X=y
CONFIG_DRIVERS_DISTANCE_SENSOR_VL53L1X=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
CONFIG_DRIVERS_LIGHTS_RGBLED_NCP5623C=y
CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8308=y
Expand Down
1 change: 1 addition & 0 deletions platforms/common/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,7 @@ add_library(px4_platform STATIC
shutdown.cpp
spi.cpp
pab_manifest.c
Serial.cpp
${SRCS}
)
target_link_libraries(px4_platform prebuild_targets px4_work_queue)
Expand Down
138 changes: 138 additions & 0 deletions platforms/common/Serial.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,138 @@
/****************************************************************************
*
* Copyright (C) 2023 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/

#include <px4_platform_common/Serial.hpp>

namespace device
{

Serial::Serial(const char *port, uint32_t baudrate, ByteSize bytesize, Parity parity, StopBits stopbits,
FlowControl flowcontrol) :
_impl(port, baudrate, bytesize, parity, stopbits, flowcontrol)
{
// If no baudrate was specified then set it to a reasonable default value
if (baudrate == 0) {
(void) _impl.setBaudrate(9600);
}
}

Serial::~Serial()
{
}

bool Serial::open()
{
return _impl.open();
}

bool Serial::isOpen() const
{
return _impl.isOpen();
}

bool Serial::close()
{
return _impl.close();
}

ssize_t Serial::read(uint8_t *buffer, size_t buffer_size)
{
return _impl.read(buffer, buffer_size);
}

ssize_t Serial::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count, uint32_t timeout_us)
{
return _impl.readAtLeast(buffer, buffer_size, character_count, timeout_us);
}

ssize_t Serial::write(const void *buffer, size_t buffer_size)
{
return _impl.write(buffer, buffer_size);
}

uint32_t Serial::getBaudrate() const
{
return _impl.getBaudrate();
}

bool Serial::setBaudrate(uint32_t baudrate)
{
return _impl.setBaudrate(baudrate);
}

ByteSize Serial::getBytesize() const
{
return _impl.getBytesize();
}

bool Serial::setBytesize(ByteSize bytesize)
{
return _impl.setBytesize(bytesize);
}

Parity Serial::getParity() const
{
return _impl.getParity();
}

bool Serial::setParity(Parity parity)
{
return _impl.setParity(parity);
}

StopBits Serial::getStopbits() const
{
return _impl.getStopbits();
}

bool Serial::setStopbits(StopBits stopbits)
{
return _impl.setStopbits(stopbits);
}

FlowControl Serial::getFlowcontrol() const
{
return _impl.getFlowcontrol();
}

bool Serial::setFlowcontrol(FlowControl flowcontrol)
{
return _impl.setFlowcontrol(flowcontrol);
}

const char *Serial::getPort() const
{
return _impl.getPort();
}

} // namespace device
97 changes: 97 additions & 0 deletions platforms/common/include/px4_platform_common/Serial.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,97 @@
/****************************************************************************
*
* Copyright (C) 2023 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/

#pragma once

#include <SerialImpl.hpp>

#include <px4_platform_common/SerialCommon.hpp>

using device::SerialConfig::ByteSize;
using device::SerialConfig::Parity;
using device::SerialConfig::StopBits;
using device::SerialConfig::FlowControl;

namespace device __EXPORT
{

class Serial
{
public:
Serial(const char *port, uint32_t baudrate = 57600,
ByteSize bytesize = ByteSize::EightBits, Parity parity = Parity::None,
StopBits stopbits = StopBits::One, FlowControl flowcontrol = FlowControl::Disabled);
virtual ~Serial();

// Open sets up the port and gets it configured based on desired configuration
bool open();
bool isOpen() const;

bool close();

ssize_t read(uint8_t *buffer, size_t buffer_size);
ssize_t readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count = 1, uint32_t timeout_us = 0);

ssize_t write(const void *buffer, size_t buffer_size);

// If port is already open then the following configuration functions
// will reconfigure the port. If the port is not yet open then they will
// simply store the configuration in preparation for the port to be opened.

uint32_t getBaudrate() const;
bool setBaudrate(uint32_t baudrate);

ByteSize getBytesize() const;
bool setBytesize(ByteSize bytesize);

Parity getParity() const;
bool setParity(Parity parity);

StopBits getStopbits() const;
bool setStopbits(StopBits stopbits);

FlowControl getFlowcontrol() const;
bool setFlowcontrol(FlowControl flowcontrol);

const char *getPort() const;

private:
// Disable copy constructors
Serial(const Serial &);
Serial &operator=(const Serial &);

// platform implementation
SerialImpl _impl;
};

} // namespace device
70 changes: 70 additions & 0 deletions platforms/common/include/px4_platform_common/SerialCommon.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,70 @@
/****************************************************************************
*
* Copyright (C) 2023 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/

#pragma once

namespace device
{
namespace SerialConfig
{


// ByteSize: number of data bits
enum class ByteSize {
FiveBits = 5,
SixBits = 6,
SevenBits = 7,
EightBits = 8,
};

// Parity: enable parity checking
enum class Parity {
None = 0,
Odd = 1,
Even = 2,
};

// StopBits: number of stop bits
enum class StopBits {
One = 1,
Two = 2
};

// FlowControl: enable flow control
enum class FlowControl {
Disabled = 0,
Enabled = 1,
};

} // namespace SerialConfig
} // namespace device
13 changes: 11 additions & 2 deletions platforms/common/include/px4_platform_common/time.h
Original file line number Diff line number Diff line change
Expand Up @@ -13,11 +13,21 @@ __END_DECLS
#define px4_clock_gettime system_clock_gettime
#endif

#if defined(ENABLE_LOCKSTEP_SCHEDULER)
#if defined(ENABLE_LOCKSTEP_SCHEDULER) || defined(__PX4_QURT)

__BEGIN_DECLS
__EXPORT int px4_clock_settime(clockid_t clk_id, const struct timespec *tp);
__END_DECLS

#else

#define px4_clock_settime system_clock_settime

#endif

#if defined(ENABLE_LOCKSTEP_SCHEDULER)

__BEGIN_DECLS
__EXPORT int px4_usleep(useconds_t usec);
__EXPORT unsigned int px4_sleep(unsigned int seconds);
__EXPORT int px4_pthread_cond_timedwait(pthread_cond_t *cond,
Expand All @@ -27,7 +37,6 @@ __END_DECLS

#else

#define px4_clock_settime system_clock_settime
#define px4_usleep system_usleep
#define px4_sleep system_sleep
#define px4_pthread_cond_timedwait system_pthread_cond_timedwait
Expand Down
Loading

0 comments on commit 69028f3

Please sign in to comment.