pdu.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2018 New Eagle
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of New Eagle nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 // Example block for PDU relay blocks.
00036 // pdu_msgs::RelayCommand msg;
00037 // msg.relay_1.value = pdu_msgs::RelayState::RELAY_ON;
00038 // pdu1_relay_pub_.publish(msg);
00039 
00040 #include <sstream>
00041 
00042 #include "pdu.h"
00043 
00044 namespace NewEagle
00045 {
00046   pdu::pdu(ros::NodeHandle &node, ros::NodeHandle &priv_nh)
00047   {
00048     int32_t id;
00049     priv_nh.getParam("id", id);
00050     priv_nh.getParam("pdu_dbc_file", pduFile_);
00051 
00052     id_ = (uint32_t)id;
00053 
00054     relayCommandAddr_ = RELAY_COMMAND_BASE_ADDR + (id_ * 256);
00055     relayStatusAddr_ = RELAY_STATUS_BASE_ADDR + id_;
00056     fuseStatusAddr_ = FUSE_STATUS_BASE_ADDR + id_;
00057 
00058     // This should be a class, initialized with a unique CAN ID
00059     pduDbc_ = NewEagle::DbcBuilder().NewDbc(pduFile_);
00060 
00061     count_ = 0;
00062     // Set up Publishers
00063     pub_can_ = node.advertise<can_msgs::Frame>("can_tx", 10);
00064 
00065     relay_report_pub_ = node.advertise<pdu_msgs::RelayReport>("relay_report", 2);
00066     fuse_report_pub_ = node.advertise<pdu_msgs::FuseReport>("fuse_report", 2);
00067 
00068     // Set up Subscribers
00069     sub_can_ = node.subscribe("can_rx", 100, &pdu::recvCAN, this, ros::TransportHints().tcpNoDelay(true));
00070 
00071     sub_relay_cmd_ = node.subscribe("relay_cmd", 1, &pdu::recvRelayCmd, this, ros::TransportHints().tcpNoDelay(true));
00072   }
00073 
00074   void pdu::recvCAN(const can_msgs::Frame::ConstPtr& msg)
00075   {
00076     if (!msg->is_rtr && !msg->is_error && msg->is_extended)
00077     {
00078       if (msg->id == relayStatusAddr_)
00079       {
00080         ROS_INFO("Relay Status");
00081 
00082         NewEagle::DbcMessage* message = pduDbc_.GetMessage("RelayStatus");
00083         message->SetFrame(msg);
00084 
00085         pdu_msgs::RelayReport out;
00086 
00087         out.relay_1.value = message->GetSignal("Relay1")->GetResult();
00088         out.relay_2.value = message->GetSignal("Relay2")->GetResult();
00089         out.relay_3.value = message->GetSignal("Relay3")->GetResult();
00090         out.relay_4.value = message->GetSignal("Relay4")->GetResult();
00091         out.relay_5.value = message->GetSignal("Relay5")->GetResult();
00092         out.relay_6.value = message->GetSignal("Relay6")->GetResult();
00093         out.relay_7.value = message->GetSignal("Relay7")->GetResult();
00094         out.relay_8.value = message->GetSignal("Relay8")->GetResult();
00095 
00096         relay_report_pub_.publish(out);
00097       }
00098       else if (msg->id == fuseStatusAddr_)
00099       {
00100         ROS_INFO("Fuse Status");
00101 
00102         NewEagle::DbcMessage* message = pduDbc_.GetMessage("FuseStatus");
00103         message->SetFrame(msg);
00104 
00105         pdu_msgs::FuseReport out;
00106 
00107         out.fuse_1.value = message->GetSignal("Fuse1")->GetResult();
00108         out.fuse_2.value = message->GetSignal("Fuse2")->GetResult();
00109         out.fuse_3.value = message->GetSignal("Fuse3")->GetResult();
00110         out.fuse_4.value = message->GetSignal("Fuse4")->GetResult();
00111         out.fuse_5.value = message->GetSignal("Fuse5")->GetResult();
00112         out.fuse_6.value = message->GetSignal("Fuse6")->GetResult();
00113         out.fuse_7.value = message->GetSignal("Fuse7")->GetResult();
00114         out.fuse_8.value = message->GetSignal("Fuse8")->GetResult();
00115         out.fuse_9.value = message->GetSignal("Fuse9")->GetResult();
00116         out.fuse_10.value = message->GetSignal("Fuse10")->GetResult();
00117         out.fuse_11.value = message->GetSignal("Fuse11")->GetResult();
00118         out.fuse_12.value = message->GetSignal("Fuse12")->GetResult();
00119         out.fuse_13.value = message->GetSignal("Fuse13")->GetResult();
00120         out.fuse_14.value = message->GetSignal("Fuse14")->GetResult();
00121         out.fuse_15.value = message->GetSignal("Fuse15")->GetResult();
00122         out.fuse_16.value = message->GetSignal("Fuse16")->GetResult();
00123 
00124         fuse_report_pub_.publish(out);
00125       }
00126     }
00127   }
00128 
00129   void pdu::recvRelayCmd(const pdu_msgs::RelayCommand::ConstPtr& msg)
00130   {
00131     ROS_INFO("Relay Command");
00132 
00133     NewEagle::DbcMessage* message = pduDbc_.GetMessage("RelayCommand");
00134 
00135     message->GetSignal("MessageID")->SetResult(0x80); // Always 0x80
00136     message->GetSignal("GridAddress")->SetResult(0x00); // Always 0x00
00137 
00138     message->GetSignal("Relay1")->SetResult(msg->relay_1.value);
00139     message->GetSignal("Relay2")->SetResult(msg->relay_2.value);
00140     message->GetSignal("Relay3")->SetResult(msg->relay_3.value);
00141     message->GetSignal("Relay4")->SetResult(msg->relay_4.value);
00142     message->GetSignal("Relay5")->SetResult(msg->relay_5.value);
00143     message->GetSignal("Relay6")->SetResult(msg->relay_6.value);
00144     message->GetSignal("Relay7")->SetResult(msg->relay_7.value);
00145     message->GetSignal("Relay8")->SetResult(msg->relay_8.value);
00146 
00147     can_msgs::Frame frame = message->GetFrame();
00148 
00149     // DBC file has the base address.  Modify the ID to send to correct device
00150     frame.id = relayCommandAddr_;
00151 
00152     pub_can_.publish(frame);
00153   }
00154 }


pdu
Author(s): Ryan Borchert , Ryan Borchert
autogenerated on Mon Jun 24 2019 19:18:36