Skip to content

Commit

Permalink
feat: added mow motor current to the monitoring (#27)
Browse files Browse the repository at this point in the history
* Update monitoring.cpp

added mower amps in monitoring

* Update monitoring.cpp

added comment to see if the runner will trigger

* Update monitoring.cpp

removed // to force build

* Update monitoring.cpp

* Update monitoring.cpp

* Update monitoring.cpp

Added mow motor current to the sensor monitoring
  • Loading branch information
midevil authored May 6, 2023
1 parent 8df3b38 commit f84f948
Showing 1 changed file with 18 additions and 0 deletions.
18 changes: 18 additions & 0 deletions src/mower_logic/src/monitoring/monitoring.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,10 @@ xbot_msgs::SensorInfo si_mow_motor_temp;
ros::Publisher si_mow_motor_temp_pub;
ros::Publisher mow_motor_temp_data_pub;

xbot_msgs::SensorInfo si_mow_motor_current;
ros::Publisher si_mow_motor_current_pub;
ros::Publisher mow_motor_current_data_pub;

ros::NodeHandle *n;

ros::Time last_status_update(0);
Expand Down Expand Up @@ -87,6 +91,10 @@ void status(const mower_msgs::Status::ConstPtr &msg) {

sensor_data.data = msg->mow_esc_status.temperature_motor;
mow_motor_temp_data_pub.publish(sensor_data);

sensor_data.data = msg->mow_esc_status.current;
mow_motor_current_data_pub.publish(sensor_data);

}

void high_level_status(const mower_msgs::HighLevelStatus::ConstPtr &msg) {
Expand Down Expand Up @@ -167,6 +175,16 @@ void registerSensors() {
si_mow_motor_temp_pub = n->advertise<xbot_msgs::SensorInfo>("xbot_monitoring/sensors/" + si_mow_motor_temp.sensor_id + "/info", 1, true);
mow_motor_temp_data_pub = n->advertise<xbot_msgs::SensorDataDouble>("xbot_monitoring/sensors/" + si_mow_motor_temp.sensor_id + "/data",10);
si_mow_motor_temp_pub.publish(si_mow_motor_temp);

si_mow_motor_current.sensor_id = "om_mow_motor_current";
si_mow_motor_current.sensor_name = "Mow Motor Current";
si_mow_motor_current.value_type = xbot_msgs::SensorInfo::TYPE_DOUBLE;
si_mow_motor_current.value_description = xbot_msgs::SensorInfo::VALUE_DESCRIPTION_CURRENT;
si_mow_motor_current.unit = "A";
si_mow_motor_current_pub = n->advertise<xbot_msgs::SensorInfo>("xbot_monitoring/sensors/" + si_mow_motor_current.sensor_id + "/info", 1, true);
mow_motor_current_data_pub = n->advertise<xbot_msgs::SensorDataDouble>("xbot_monitoring/sensors/" + si_mow_motor_current.sensor_id + "/data",10);
si_mow_motor_current_pub.publish(si_mow_motor_current);


}

Expand Down

0 comments on commit f84f948

Please sign in to comment.