pdu.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018 New Eagle
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of New Eagle nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 // Example block for PDU relay blocks.
36 // pdu_msgs::RelayCommand msg;
37 // msg.relay_1.value = pdu_msgs::RelayState::RELAY_ON;
38 // pdu1_relay_pub_.publish(msg);
39 
40 #include <sstream>
41 
42 #include "pdu.h"
43 
44 namespace NewEagle
45 {
47  {
48  int32_t id;
49  priv_nh.getParam("id", id);
50  priv_nh.getParam("pdu_dbc_file", pduFile_);
51 
52  id_ = (uint32_t)id;
53 
57 
58  // This should be a class, initialized with a unique CAN ID
60 
61  count_ = 0;
62  // Set up Publishers
63  pub_can_ = node.advertise<can_msgs::Frame>("can_tx", 10);
64 
65  relay_report_pub_ = node.advertise<pdu_msgs::RelayReport>("relay_report", 2);
66  fuse_report_pub_ = node.advertise<pdu_msgs::FuseReport>("fuse_report", 2);
67 
68  // Set up Subscribers
69  sub_can_ = node.subscribe("can_rx", 100, &pdu::recvCAN, this, ros::TransportHints().tcpNoDelay(true));
70 
71  sub_relay_cmd_ = node.subscribe("relay_cmd", 1, &pdu::recvRelayCmd, this, ros::TransportHints().tcpNoDelay(true));
72  }
73 
74  void pdu::recvCAN(const can_msgs::Frame::ConstPtr& msg)
75  {
76  if (!msg->is_rtr && !msg->is_error && msg->is_extended)
77  {
78  if (msg->id == relayStatusAddr_)
79  {
80  ROS_INFO("Relay Status");
81 
82  NewEagle::DbcMessage* message = pduDbc_.GetMessage("RelayStatus");
83  message->SetFrame(msg);
84 
85  pdu_msgs::RelayReport out;
86 
87  out.relay_1.value = message->GetSignal("Relay1")->GetResult();
88  out.relay_2.value = message->GetSignal("Relay2")->GetResult();
89  out.relay_3.value = message->GetSignal("Relay3")->GetResult();
90  out.relay_4.value = message->GetSignal("Relay4")->GetResult();
91  out.relay_5.value = message->GetSignal("Relay5")->GetResult();
92  out.relay_6.value = message->GetSignal("Relay6")->GetResult();
93  out.relay_7.value = message->GetSignal("Relay7")->GetResult();
94  out.relay_8.value = message->GetSignal("Relay8")->GetResult();
95 
97  }
98  else if (msg->id == fuseStatusAddr_)
99  {
100  ROS_INFO("Fuse Status");
101 
102  NewEagle::DbcMessage* message = pduDbc_.GetMessage("FuseStatus");
103  message->SetFrame(msg);
104 
105  pdu_msgs::FuseReport out;
106 
107  out.fuse_1.value = message->GetSignal("Fuse1")->GetResult();
108  out.fuse_2.value = message->GetSignal("Fuse2")->GetResult();
109  out.fuse_3.value = message->GetSignal("Fuse3")->GetResult();
110  out.fuse_4.value = message->GetSignal("Fuse4")->GetResult();
111  out.fuse_5.value = message->GetSignal("Fuse5")->GetResult();
112  out.fuse_6.value = message->GetSignal("Fuse6")->GetResult();
113  out.fuse_7.value = message->GetSignal("Fuse7")->GetResult();
114  out.fuse_8.value = message->GetSignal("Fuse8")->GetResult();
115  out.fuse_9.value = message->GetSignal("Fuse9")->GetResult();
116  out.fuse_10.value = message->GetSignal("Fuse10")->GetResult();
117  out.fuse_11.value = message->GetSignal("Fuse11")->GetResult();
118  out.fuse_12.value = message->GetSignal("Fuse12")->GetResult();
119  out.fuse_13.value = message->GetSignal("Fuse13")->GetResult();
120  out.fuse_14.value = message->GetSignal("Fuse14")->GetResult();
121  out.fuse_15.value = message->GetSignal("Fuse15")->GetResult();
122  out.fuse_16.value = message->GetSignal("Fuse16")->GetResult();
123 
125  }
126  }
127  }
128 
129  void pdu::recvRelayCmd(const pdu_msgs::RelayCommand::ConstPtr& msg)
130  {
131  ROS_INFO("Relay Command");
132 
133  NewEagle::DbcMessage* message = pduDbc_.GetMessage("RelayCommand");
134 
135  message->GetSignal("MessageID")->SetResult(0x80); // Always 0x80
136  message->GetSignal("GridAddress")->SetResult(0x00); // Always 0x00
137 
138  message->GetSignal("Relay1")->SetResult(msg->relay_1.value);
139  message->GetSignal("Relay2")->SetResult(msg->relay_2.value);
140  message->GetSignal("Relay3")->SetResult(msg->relay_3.value);
141  message->GetSignal("Relay4")->SetResult(msg->relay_4.value);
142  message->GetSignal("Relay5")->SetResult(msg->relay_5.value);
143  message->GetSignal("Relay6")->SetResult(msg->relay_6.value);
144  message->GetSignal("Relay7")->SetResult(msg->relay_7.value);
145  message->GetSignal("Relay8")->SetResult(msg->relay_8.value);
146 
147  can_msgs::Frame frame = message->GetFrame();
148 
149  // DBC file has the base address. Modify the ID to send to correct device
150  frame.id = relayCommandAddr_;
151 
152  pub_can_.publish(frame);
153  }
154 }
NewEagle::DbcSignal * GetSignal(std::string signalName)
ros::Subscriber sub_can_
Definition: pdu.h:82
void recvCAN(const can_msgs::Frame::ConstPtr &msg)
Definition: pdu.cpp:74
void publish(const boost::shared_ptr< M > &message) const
ros::Publisher relay_report_pub_
Definition: pdu.h:88
void SetFrame(const can_msgs::Frame::ConstPtr &msg)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::Publisher pub_can_
Definition: pdu.h:86
NewEagle::Dbc NewDbc(const std::string &dbcFile)
ros::Publisher fuse_report_pub_
Definition: pdu.h:87
std::string pduFile_
Definition: pdu.h:76
uint32_t fuseStatusAddr_
Definition: pdu.h:71
void recvRelayCmd(const pdu_msgs::RelayCommand::ConstPtr &msg)
Definition: pdu.cpp:129
double GetResult() const
ros::Subscriber sub_relay_cmd_
Definition: pdu.h:83
uint32_t relayStatusAddr_
Definition: pdu.h:70
can_msgs::Frame GetFrame()
NewEagle::DbcMessage * GetMessage(std::string messageName)
#define ROS_INFO(...)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void SetResult(double result)
pdu(ros::NodeHandle &node, ros::NodeHandle &priv_nh)
Definition: pdu.cpp:46
bool getParam(const std::string &key, std::string &s) const
NewEagle::Dbc pduDbc_
Definition: pdu.h:75
uint32_t count_
Definition: pdu.h:73
uint32_t relayCommandAddr_
Definition: pdu.h:69
uint32_t id_
Definition: pdu.h:68


pdu
Author(s): Ryan Borchert
autogenerated on Sat Jan 9 2021 03:56:20