disabled onboard time sync, hoping NTP would sync.
This commit is contained in:
parent
ffbe4569cc
commit
fff1c3398d
|
@ -6,19 +6,19 @@ timesync_state = 0
|
||||||
|
|
||||||
# Function to sync. algo
|
# Function to sync. algo
|
||||||
function check_time_sync(){
|
function check_time_sync(){
|
||||||
sync_timer = sync_timer + 1
|
# sync_timer = sync_timer + 1
|
||||||
if(sync_timer < TIME_TO_SYNC){
|
# if(sync_timer < TIME_TO_SYNC){
|
||||||
log(" Synchronizing Clock : ",sync_timer,"/",TIME_TO_SYNC)
|
# log(" Synchronizing Clock : ",sync_timer,"/",TIME_TO_SYNC)
|
||||||
timesync_state = 1
|
# timesync_state = 1
|
||||||
}
|
# }
|
||||||
else{
|
# else{
|
||||||
timesync_state = 0
|
# timesync_state = 0
|
||||||
}
|
# }
|
||||||
if(timesync_old_state == 0 and timesync_state == 1){
|
# if(timesync_old_state == 0 and timesync_state == 1){
|
||||||
timesync_itr = timesync_itr + 1
|
# timesync_itr = timesync_itr + 1
|
||||||
timesync_old_state = 0
|
# timesync_old_state = 0
|
||||||
}
|
# }
|
||||||
timesync_old_state = timesync_state
|
# timesync_old_state = timesync_state
|
||||||
}
|
}
|
||||||
|
|
||||||
# Function to set sync timer to zero and reinitiate sync. algo
|
# Function to set sync timer to zero and reinitiate sync. algo
|
||||||
|
|
|
@ -204,9 +204,9 @@ void roscontroller::RosControllerRun()
|
||||||
inmsgdata.clear();
|
inmsgdata.clear();
|
||||||
log<<std::endl;
|
log<<std::endl;
|
||||||
|
|
||||||
time_sync_step();
|
// time_sync_step();
|
||||||
if(debug)
|
// if(debug)
|
||||||
ROS_INFO("[Debug : %i ] logical Time %f , har time %f",robot_id, logical_clock.toSec(), ros::Time::now().toSec());
|
// ROS_INFO("[Debug : %i ] logical Time %f , har time %f",robot_id, logical_clock.toSec(), ros::Time::now().toSec());
|
||||||
// Call Step from buzz script
|
// Call Step from buzz script
|
||||||
buzz_utility::buzz_script_step();
|
buzz_utility::buzz_script_step();
|
||||||
// Prepare messages and publish them
|
// Prepare messages and publish them
|
||||||
|
@ -616,6 +616,7 @@ with size......... | /
|
||||||
uint32_t stime = (uint32_t)(ros::Time::now().toSec()); //(uint32_t)(logical_clock.toSec() * 100000);
|
uint32_t stime = (uint32_t)(ros::Time::now().toSec()); //(uint32_t)(logical_clock.toSec() * 100000);
|
||||||
memcpy((void*)(tmphead+2),(void*)&stime,sizeof(uint32_t));
|
memcpy((void*)(tmphead+2),(void*)&stime,sizeof(uint32_t));
|
||||||
uint64_t rheader[1];
|
uint64_t rheader[1];
|
||||||
|
rheader[0]=0;
|
||||||
payload_out.sysid = (uint8_t)robot_id;
|
payload_out.sysid = (uint8_t)robot_id;
|
||||||
payload_out.msgid = (uint32_t)message_number;
|
payload_out.msgid = (uint32_t)message_number;
|
||||||
|
|
||||||
|
@ -1128,7 +1129,7 @@ void roscontroller::payload_obt(const mavros_msgs::Mavlink::ConstPtr& msg)
|
||||||
uint32_t temptime=0;
|
uint32_t temptime=0;
|
||||||
memcpy(&temptime, r16head+2, sizeof(uint32_t));
|
memcpy(&temptime, r16head+2, sizeof(uint32_t));
|
||||||
float stime = (float)temptime/(float)100000;
|
float stime = (float)temptime/(float)100000;
|
||||||
if(debug) ROS_INFO("Received Msg: sent time %f for id %u",stime, mid);
|
// if(debug) ROS_INFO("Received Msg: sent time %f for id %u",stime, mid);
|
||||||
// Check for Updater message, if updater message push it into updater FIFO
|
// Check for Updater message, if updater message push it into updater FIFO
|
||||||
if ((uint64_t)msg->payload64[0] == (uint64_t)UPDATER_MESSAGE)
|
if ((uint64_t)msg->payload64[0] == (uint64_t)UPDATER_MESSAGE)
|
||||||
{
|
{
|
||||||
|
|
Loading…
Reference in New Issue