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

Implemented CAN logging - 260 #455

Open
wants to merge 4 commits into
base: main
Choose a base branch
from
Open
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
6 changes: 6 additions & 0 deletions scripts/test.sh
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,12 @@ if [ -d $NET_DIR ]; then
popd
fi

# Set the environment variables
export ROS_LOG_DIR="/src/network_systems/scripts/can_transceiver.log"
export RCUTILS_COLORIZED_OUTPUT="1"

echo "ROS_LOG_DIR is set to: $ROS_LOG_DIR"

colcon test --packages-ignore virtual_iridium --merge-install --event-handlers console_cohesion+
colcon test-result
exit 0
17 changes: 11 additions & 6 deletions src/network_systems/launch/main_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
from launch_ros.actions import Node

from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, OpaqueFunction
from launch.actions import DeclareLaunchArgument, OpaqueFunction, SetEnvironmentVariable
from launch.launch_context import LaunchContext
from launch.some_substitutions_type import SomeSubstitutionsType
from launch.substitutions import LaunchConfiguration
Expand Down Expand Up @@ -81,6 +81,11 @@ def setup_launch(context: LaunchContext) -> List[Node]:
Returns:
List[Nodes]: Nodes to launch.
"""
mode = LaunchConfiguration("mode").perform(context)
if mode == "development":
SetEnvironmentVariable(
name="ROS_LOG_DIR", value="/workspaces/sailbot_workspace/log"
).visit(context)
launch_description_entities = list()
launch_description_entities.append(get_cached_fib_description(context))
launch_description_entities.append(get_mock_ais_description(context))
Expand Down Expand Up @@ -221,12 +226,12 @@ def get_remote_transceiver_description(context: LaunchContext) -> Node:
def get_local_transceiver_description(context: LaunchContext) -> Node:
"""Gets the launch description for the local_transceiver_node.

Args:
context (LaunchContext): The current launch context.
Args:
context (LaunchContext): The current launch context.

Returns:
Node: The node object that launches the local_transceiver_node.
"""
Returns:
Node: The node object that launches the local_transceiver_node.
"""
node_name = "local_transceiver_node"
ros_parameters = [
global_launch_config,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -135,6 +135,12 @@ class BaseFrame
* @return A string that can be printed or logged for debugging
*/
virtual std::string debugStr() const;

/**
* @brief A string representation of the dataframe
*
*/
virtual std::string toString() const;
};

/**
Expand Down Expand Up @@ -186,6 +192,12 @@ class Battery final : public BaseFrame
*/
std::string debugStr() const override;

/**
* @brief A string representation of the Battery object
*
*/
std::string toString() const override;

private:
/**
* @brief Private helper constructor for Battery objects
Expand Down Expand Up @@ -252,6 +264,12 @@ class MainTrimTab final : public BaseFrame
*/
std::string debugStr() const override;

/**
* @brief A string representation of the MainTrimTab object
*
*/
std::string toString() const override;

private:
/**
* @brief Private helper constructor for MainTrimTab objects
Expand Down Expand Up @@ -317,6 +335,12 @@ class WindSensor final : public BaseFrame
*/
std::string debugStr() const override;

/**
* @brief A string representation of the WindSensor object
*
*/
std::string toString() const override;

/**
* @brief Factory method to convert the index of a wind sensor in the custom_interfaces ROS representation
* into a CanId if valid.
Expand Down Expand Up @@ -397,6 +421,12 @@ class GPS final : public BaseFrame
*/
std::string debugStr() const override;

/**
* @brief A string representation of the GPS object
*
*/
std::string toString() const override;

private:
/**
* @brief Private helper constructor for GPS objects
Expand Down Expand Up @@ -476,6 +506,12 @@ class AISShips final : public BaseFrame
*/
std::string debugStr() const override;

/**
* @brief A string representation of the AISShips object
*
*/
std::string toString() const override;

/**
* @brief Returns the number of ships
*
Expand Down Expand Up @@ -639,6 +675,12 @@ class DesiredHeading final : public BaseFrame
*/
std::string debugStr() const override;

/**
* @brief A string representation of the DesiredHeading object
*
*/
std::string toString() const override;

private:
/**
* @brief Private helper constructor for DesiredHeading objects
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,8 @@ BaseFrame::BaseFrame(std::span<const CanId> valid_ids, CanId id, uint8_t can_byt

std::string BaseFrame::debugStr() const { return CanDebugStr(id_); }

std::string BaseFrame::toString() const { return CanIdToStr(id_); }

CanFrame BaseFrame::toLinuxCan() const { return CanFrame{.can_id = static_cast<canid_t>(id_), .len = can_byte_dlen_}; }

// BaseFrame protected END
Expand Down Expand Up @@ -123,6 +125,13 @@ std::string Battery::debugStr() const
return ss.str();
}

std::string Battery::toString() const
{
std::stringstream ss;
ss << "[BATTERY] Voltage: " << volt_;
return ss.str();
}

// Battery public END
// Battery private START

Expand Down Expand Up @@ -190,6 +199,13 @@ std::string MainTrimTab::debugStr() const
return ss.str();
}

std::string MainTrimTab::toString() const
{
std::stringstream ss;
ss << "[MAIN TRIM TAB] Angle: " << angle_;
return ss.str();
}

// MainTrimTab public END
// MainTrimTab private START

Expand Down Expand Up @@ -263,6 +279,13 @@ std::string WindSensor::debugStr() const
return ss.str();
}

std::string WindSensor::toString() const
{
std::stringstream ss;
ss << "[WIND SENSOR] Speed: " << wind_speed_ << " Angle: " << wind_angle_;
return ss.str();
}

std::optional<CanId> WindSensor::rosIdxToCanId(size_t wind_idx)
{
if (wind_idx < WIND_SENSOR_IDS.size()) {
Expand Down Expand Up @@ -381,6 +404,13 @@ std::string GPS::debugStr() const
return ss.str();
}

std::string GPS::toString() const
{
std::stringstream ss;
ss << "[GPS] Latitude: " << lat_ << " Longitude: " << lon_ << " Speed: " << speed_; //NOTE HEADING IS NOT USED
return ss.str();
}

//GPS public END
//GPS private START

Expand Down Expand Up @@ -550,6 +580,13 @@ std::string AISShips::debugStr() const

return ss.str();
}

std::string AISShips::toString() const
{
std::stringstream ss;
ss << "[AIS SHIP] ID: " << ship_id_ << " Latitude: " << lat_ << " Longitude: " << lon_;
return ss.str();
}
//AISShips public END
//AISShips private START

Expand Down Expand Up @@ -698,6 +735,13 @@ std::string DesiredHeading::debugStr() const
return ss.str();
}

std::string DesiredHeading::toString() const
{
std::stringstream ss;
ss << "[DESIRED HEADING] Heading: " << heading_;
return ss.str();
}

// DesiredHeading public END
// DesiredHeading private START

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,7 @@ class CanTransceiverIntf : public NetNode
this->create_publisher<msg::CanSimToBoatSim>(ros_topics::BOAT_SIM_INPUT, QUEUE_SIZE);

timer_ = this->create_wall_timer(TIMER_INTERVAL, [this]() {
mockBatteriesCb();
//mockBatteriesCb();
publishBoatSimInput(boat_sim_input_msg_);
// Add any other necessary looping callbacks
});
Expand Down Expand Up @@ -172,6 +172,7 @@ class CanTransceiverIntf : public NetNode
ais_ships_holder_.clear();
ais_ships_num_ = 0; // reset the number of ships
}
RCLCPP_INFO(this->get_logger(), "%s %s", getCurrentTimeString().c_str(), ais_ship.toString().c_str());
}

/**
Expand All @@ -195,6 +196,17 @@ class CanTransceiverIntf : public NetNode
}
CAN_FP::PwrMode power_mode(set_pwr_mode, CAN_FP::CanId::PWR_MODE);
can_trns_->send(power_mode.toLinuxCan());

// Get the current time as a time_point
auto now = std::chrono::system_clock::now();

// Convert it to a time_t object for extracting hours and minutes
std::time_t currentTime = std::chrono::system_clock::to_time_t(now);

std::stringstream ss;
ss << currentTime;

RCLCPP_INFO(this->get_logger(), "%s %s", getCurrentTimeString().c_str(), bat.toString().c_str());
}

/**
Expand All @@ -209,6 +221,7 @@ class CanTransceiverIntf : public NetNode

msg::GPS gps_ = gps.toRosMsg();
gps_pub_->publish(gps_);
RCLCPP_INFO(this->get_logger(), "%s %s", getCurrentTimeString().c_str(), gps.toString().c_str());
}

/**
Expand All @@ -229,8 +242,8 @@ class CanTransceiverIntf : public NetNode
msg::WindSensor & wind_sensor_msg = wind_sensors_.wind_sensors[idx];
wind_sensor_msg = wind_sensor.toRosMsg();
wind_sensors_pub_->publish(wind_sensors_);

publishFilteredWindSensor();
RCLCPP_INFO(this->get_logger(), "%s %s", getCurrentTimeString().c_str(), wind_sensor.toString().c_str());
}

/**
Expand Down Expand Up @@ -260,6 +273,9 @@ class CanTransceiverIntf : public NetNode
filtered_wind_sensor_.set__direction(static_cast<int16_t>(average_direction));

filtered_wind_sensor_pub_->publish(filtered_wind_sensor_);
std::stringstream ss;
ss << "[WIND SENSOR] Speed: " << filtered_speed.speed << " Angle: " << average_direction;
RCLCPP_INFO(this->get_logger(), "%s %s", getCurrentTimeString().c_str(), ss.str().c_str());
}

/**
Expand All @@ -286,6 +302,9 @@ class CanTransceiverIntf : public NetNode
generic_sensor_msg.set__id(generic_frame.can_id);

generic_sensors_pub_->publish(generic_sensors_);
std::stringstream ss;
ss << "[GENERIC SENSOR] CanID: " << generic_frame.can_id << " Data: " << generic_data;
RCLCPP_INFO(this->get_logger(), "%s %s", getCurrentTimeString().c_str(), ss.str().c_str());
}

// SIMULATION CALLBACKS //
Expand All @@ -309,8 +328,10 @@ class CanTransceiverIntf : public NetNode
{
sail_cmd_ = sail_cmd_input;
boat_sim_input_msg_.set__sail_cmd(sail_cmd_);

can_trns_->send(CAN_FP::MainTrimTab(sail_cmd_input, CanId::MAIN_TR_TAB).toLinuxCan());
auto main_trim_tab_frame = CAN_FP::MainTrimTab(sail_cmd_input, CanId::MAIN_TR_TAB);
can_trns_->send(main_trim_tab_frame.toLinuxCan());
RCLCPP_INFO(
this->get_logger(), "%s %s", getCurrentTimeString().c_str(), main_trim_tab_frame.toString().c_str());
}

/**
Expand All @@ -331,7 +352,10 @@ class CanTransceiverIntf : public NetNode
void subDesiredHeadingCb(msg::DesiredHeading desired_heading)
{
boat_sim_input_msg_.set__heading(desired_heading);
can_trns_->send(CAN_FP::DesiredHeading(desired_heading, CanId::MAIN_TR_TAB).toLinuxCan());
auto desired_heading_frame = CAN_FP::DesiredHeading(desired_heading, CanId::MAIN_TR_TAB);
can_trns_->send(desired_heading_frame.toLinuxCan());
RCLCPP_INFO(
this->get_logger(), "%s %s", getCurrentTimeString().c_str(), desired_heading_frame.toString().c_str());
}

/**
Expand Down Expand Up @@ -361,6 +385,18 @@ class CanTransceiverIntf : public NetNode

can_trns_->send(CAN_FP::Battery(bat, CanId::BMS_DATA_FRAME).toLinuxCan());
}
static std::string getCurrentTimeString()
{
auto now = rclcpp::Clock().now();
std::time_t time_now = static_cast<std::time_t>(now.seconds());
std::tm time_info;
localtime_r(&time_now, &time_info);

std::ostringstream ss;
ss << '[' << std::put_time(&time_info, "%Y-%m-%d %H:%M:%S") << ']';

return ss.str();
}
};

int main(int argc, char * argv[])
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -1157,9 +1157,8 @@ TEST_F(TestCanTransceiver, TestNewGPSValid)
*/
TEST_F(TestCanTransceiver, TestNewDataWindValid)
{
volatile bool is_cb_called = false;

std::function<void(CAN_FP::CanFrame)> test_cb = [&is_cb_called](CAN_FP::CanFrame /*unused*/) {
volatile bool is_cb_called = false;
std::function<void(CAN_FP::CanFrame)> test_cb = [&is_cb_called](CAN_FP::CanFrame /*unused*/) {
is_cb_called = true;
};
canbus_t_->registerCanCbs({{
Expand Down
Loading